mirror of
https://gitee.com/Vancouver2017/luban-lite-t3e-pro.git
synced 2025-12-14 18:38:55 +00:00
V1.0.5
This commit is contained in:
@@ -143,12 +143,18 @@ struct can_bittiming_const {
|
||||
};
|
||||
|
||||
typedef enum {
|
||||
CAN_NORMAL_MODE = 0,
|
||||
CAN_RESET_MODE = BIT(0),
|
||||
CAN_LISTEN_MODE = BIT(1),
|
||||
CAN_SELFTEST_MODE = BIT(2),
|
||||
CAN_SLEEP_MODE = BIT(4),
|
||||
} can_mode_t;
|
||||
|
||||
enum {
|
||||
CAN_FRAME_TYPE_DATA = 0,
|
||||
CAN_FRAME_TYPE_REMOTE = 1,
|
||||
};
|
||||
|
||||
typedef enum {
|
||||
TX_REQ = BIT(0),
|
||||
ABORT_REQ = BIT(1),
|
||||
@@ -188,15 +194,16 @@ typedef struct {
|
||||
|
||||
typedef struct can_handle can_handle;
|
||||
struct can_handle {
|
||||
unsigned long can_base;
|
||||
u32 irq_num;
|
||||
u32 clk_id;
|
||||
u32 idx;
|
||||
void (*callback)(can_handle * phandle, void *arg);
|
||||
void *arg;
|
||||
u32 baudrate;
|
||||
can_msg_t msg;
|
||||
can_status_t status;
|
||||
unsigned long can_base;
|
||||
u32 irq_num;
|
||||
u32 clk_id;
|
||||
u32 idx;
|
||||
void (*callback)(can_handle * phandle, void *arg);
|
||||
void *arg;
|
||||
u32 baudrate;
|
||||
can_msg_t msg;
|
||||
can_status_t status;
|
||||
unsigned long mode;
|
||||
};
|
||||
|
||||
typedef enum {
|
||||
|
||||
@@ -14,7 +14,7 @@ extern "C" {
|
||||
struct aic_clk_comm_cfg {
|
||||
struct aic_clk_ops *ops;
|
||||
const char *name;
|
||||
bool enable_count;
|
||||
bool enable;
|
||||
};
|
||||
|
||||
struct aic_clk_fixed_rate_cfg {
|
||||
@@ -117,6 +117,12 @@ struct aic_clk {
|
||||
u8 flag;
|
||||
};
|
||||
|
||||
struct aic_pll_vco {
|
||||
unsigned long vco_min;
|
||||
unsigned long vco_max;
|
||||
char *name;
|
||||
};
|
||||
|
||||
struct aic_clk_ops {
|
||||
int (*enable)(struct aic_clk_comm_cfg *comm_cfg);
|
||||
void (*disable)(struct aic_clk_comm_cfg *comm_cfg);
|
||||
@@ -148,7 +154,7 @@ struct aic_clk_ops {
|
||||
.id = _id, \
|
||||
.parent_id = 0, \
|
||||
.rate = _rate, \
|
||||
.comm.enable_count = 1, \
|
||||
.comm.enable = 1, \
|
||||
.comm.ops = &aic_clk_fixed_rate_ops, \
|
||||
.comm.name = _name, \
|
||||
}
|
||||
|
||||
@@ -469,7 +469,8 @@ void de_config_timing(void *base_addr,
|
||||
u32 active_w, u32 active_h,
|
||||
u32 hfp, u32 hbp,
|
||||
u32 vfp, u32 vbp,
|
||||
u32 hsync, u32 vsync);
|
||||
u32 hsync, u32 vsync,
|
||||
u32 h_pol, u32 v_pol);
|
||||
|
||||
void de_set_blending_size(void *base_addr,
|
||||
u32 active_w, u32 active_h);
|
||||
|
||||
@@ -12,11 +12,12 @@
|
||||
#include "aic_hal_disp_reg_util.h"
|
||||
|
||||
enum dsi_mode {
|
||||
DSI_MOD_VID_PULSE = 0,
|
||||
DSI_MOD_VID_EVENT = 1,
|
||||
DSI_MOD_VID_BURST = 2,
|
||||
DSI_MOD_CMD_MODE = 3,
|
||||
DSI_MOD_MAX
|
||||
DSI_MOD_VID_PULSE = BIT(0),
|
||||
DSI_MOD_VID_EVENT = BIT(1),
|
||||
DSI_MOD_VID_BURST = BIT(2),
|
||||
DSI_MOD_CMD_MODE = BIT(3),
|
||||
|
||||
DSI_CLOCK_NON_CONTINUOUS = BIT(4),
|
||||
};
|
||||
|
||||
enum dsi_format {
|
||||
@@ -75,7 +76,7 @@ enum dsi_format {
|
||||
#define DSI_VID_MODE_CFG_LP_EN_VBP BIT(9)
|
||||
#define DSI_VID_MODE_CFG_LP_EN_VSA BIT(8)
|
||||
#define DSI_VID_MODE_CFG_TYPE_MASK GENMASK(1, 0)
|
||||
#define DSI_VID_MODE_CFG_TYPE(x) (((x) & 0x3) << 0)
|
||||
#define DSI_VID_MODE_CFG_TYPE(x) ((((x) >> 1) & 0x3) << 0)
|
||||
|
||||
#define DSI_VID_HBP_TIME_MASK GENMASK(27, 16)
|
||||
#define DSI_VID_HBP_TIME(x) (((x) & 0xFFF) << 16)
|
||||
@@ -319,7 +320,7 @@ void dsi_set_data_clk_polrs(void *base, u32 dc_inv);
|
||||
|
||||
void dsi_set_clk_div(void *base, ulong mclk, ulong lp_rate);
|
||||
void dsi_pkg_init(void *base);
|
||||
void dsi_phy_init(void *base, ulong mclk, u32 lane);
|
||||
void dsi_phy_init(void *base, ulong mclk, u32 lane, enum dsi_mode mode);
|
||||
void dsi_hs_clk(void *base, u32 enable);
|
||||
void dsi_set_vm(void *base, enum dsi_mode mode, enum dsi_format format,
|
||||
u32 lane, u32 vc, const struct display_timing *timing);
|
||||
|
||||
@@ -111,6 +111,8 @@ int hal_gpio_set_debounce(unsigned int group, unsigned int pin,
|
||||
|
||||
int hal_gpio_cfg(struct gpio_cfg *cfg, u32 cnt);
|
||||
int hal_gpio_get_pincfg(unsigned int group, unsigned int pin, int check_type);
|
||||
int hal_gpio_get_outcfg(unsigned int group, unsigned int pin,
|
||||
unsigned int *pvalue);
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
|
||||
@@ -44,6 +44,12 @@ enum lvds_swap {
|
||||
LVDS_D3 = 0x4
|
||||
};
|
||||
|
||||
#define LVDS_LANES(x0, x1, x2, x3, x4) ((((x0) & 0xF) << 16) | \
|
||||
(((x1) & 0xF) << 12) | \
|
||||
(((x2) & 0xF) << 8) | \
|
||||
(((x3) & 0xF) << 4) | \
|
||||
(((x4) & 0xF) << 0)) \
|
||||
|
||||
#define LVDS_CTL_MODE_MASK GENMASK(9, 8)
|
||||
#define LVDS_CTL_MODE(x) (((x) & 0x3) << 8)
|
||||
#define LVDS_CTL_LINK_MASK GENMASK(5, 4)
|
||||
|
||||
@@ -80,11 +80,8 @@ enum aic_rgb_cko_phase_sel {
|
||||
|
||||
#define RGB_DATA_OUT_SEL_MASK GENMASK(2, 0)
|
||||
#define RGB_DATA_OUT_SEL(x) (((x) & 0x7) << 0)
|
||||
#define RGB_DATA_OUT_SEL_MASK GENMASK(2, 0)
|
||||
#define RGB_DATA_OUT_SEL(x) (((x) & 0x7) << 0)
|
||||
#define RGB_DATA_OUT_SEL_VALID_MASK GENMASK(14,4)
|
||||
#define RGB_DATA_OUT_SEL_VALID_8BITS 0x7770
|
||||
#define RGB_DATA_OUT_SEL_VALID_6BITS 0x5550
|
||||
#define RGB_DATA_OUT_SEL_VALID_MASK GENMASK(14, 4)
|
||||
#define RGB_DATA_OUT_SEL_VALID(x) (((x) & 0xFFF) << 4)
|
||||
|
||||
#define CKO_PHASE_SEL_MASK GENMASK(1, 0)
|
||||
#define CKO_PHASE_SEL(x) (((x) & 0x3) << 0)
|
||||
|
||||
@@ -45,8 +45,8 @@ extern "C" {
|
||||
#define LCR_STOP_BIT1 0xfb /* 1 stop bit */
|
||||
#define LCR_STOP_BIT2 0x04 /* 1.5 stop bit */
|
||||
|
||||
#define HALT_HALT_TX_DISABLE 0x00
|
||||
#define HALT_HALT_TX_ENABLE 0x01
|
||||
#define HALT_TX_DISABLE 0x00
|
||||
#define HALT_TX_ENABLE 0x01
|
||||
#define HALT_CHCFG_AT_BUSY 0x02
|
||||
#define HALT_CHANGE_UPDATE 0x04
|
||||
|
||||
@@ -72,6 +72,7 @@ extern "C" {
|
||||
#define AIC_UART_MCR_UART 0x00
|
||||
#define AIC_UART_MCR_FUNC_MASK 0x3F
|
||||
#define AIC_UART_MCR_FLOW_CTRL 0x22 /* Auto Flow Control Enable */
|
||||
#define AIC_UART_MCR_RTS_CTRL 0x02 /* RTS Control */
|
||||
|
||||
#define AIC_UART_EXREG 0xB8 /* RS485 DE Time */
|
||||
#define AIC_UART_RS485_CTL_MODE 0x80;
|
||||
@@ -87,6 +88,7 @@ extern "C" {
|
||||
#define AIC_UART_232_RESUME_DATA 0x83
|
||||
#define AIC_UART_232_SUSPEND_DATA 0x84
|
||||
#define AIC_UART_SW_FLOW_CTRL 0x85
|
||||
#define AIC_UART_SW_RECEIVE_ON_OFF 0x86
|
||||
|
||||
#define AIC_UART_DEV_MODE_RS485 0x1
|
||||
|
||||
@@ -123,6 +125,7 @@ typedef enum
|
||||
USART_MODE_RS232_UNAUTO_FLOW_CTRL = 4, ///< RS232 hardware unauto flow conctrol
|
||||
USART_MODE_RS232_SW_FLOW_CTRL = 5, ///< RS232 software flow conctrol
|
||||
USART_MODE_RS232_SW_HW_FLOW_CTRL = 6, ///< RS232 software and hardware flow conctrol
|
||||
USART_FUNC_RS485_SIMULATION = 7, ///< RS485 simulation
|
||||
} usart_func_e;
|
||||
|
||||
/****** USART specific error codes *****/
|
||||
|
||||
@@ -246,6 +246,16 @@ static inline void hal_audio_disable_fade(aic_audio_ctrl *codec)
|
||||
writel(0, codec->reg_base + FADE_CTRL0_REG);
|
||||
}
|
||||
|
||||
static inline void hal_audio_enable_dmic_adout_shift(aic_audio_ctrl *codec)
|
||||
{
|
||||
uint32_t reg_val;
|
||||
|
||||
reg_val = readl(codec->reg_base + RX_DMIC_IF_CTRL_REG);
|
||||
reg_val &= ~(RX_DMIC_IF_ADOUT_SHIFT_MASK);
|
||||
reg_val |= (RX_DMIC_IF_ADOUT_SHIFT_EN | RX_DMIC_IF_ADOUT_SHIFT(3));
|
||||
writel(reg_val, codec->reg_base + RX_DMIC_IF_CTRL_REG);
|
||||
}
|
||||
|
||||
int hal_audio_init(aic_audio_ctrl *codec);
|
||||
int hal_audio_uninit(aic_audio_ctrl *codec);
|
||||
void hal_audio_set_samplerate(aic_audio_ctrl *codec, uint32_t samplerate);
|
||||
|
||||
@@ -13,6 +13,7 @@
|
||||
#define RX_DMIC_IF_CTRL_REG (0x00)
|
||||
#define RX_DMIC_IF_ADOUT_SHIFT_EN BIT(15)
|
||||
#define RX_DMIC_IF_ADOUT_SHIFT_MASK GENMASK(14, 12)
|
||||
#define RX_DMIC_IF_ADOUT_SHIFT(fs) ((fs) << 12)
|
||||
#define RX_DMIC_IF_DLT_LENGTH (10)
|
||||
#define RX_DMIC_IF_DMIC_RX_DLT_EN (9)
|
||||
#define RX_DMIC_IF_DEC2_FLT BIT(7)
|
||||
|
||||
@@ -31,6 +31,15 @@ enum dma_transfer_direction {
|
||||
DMA_TRANS_NONE,
|
||||
};
|
||||
|
||||
enum dma_transfer_type {
|
||||
TYPE_IO_SINGLE = 0,
|
||||
TYPE_BURST = 1,
|
||||
TYPE_MEMORY = 2,
|
||||
TYPE_MEMORYSET = 3,
|
||||
TYPE_IO_FAST = 4,
|
||||
TYPE_IO_AUTO = 10,
|
||||
};
|
||||
|
||||
enum dma_slave_buswidth {
|
||||
DMA_SLAVE_BUSWIDTH_UNDEFINED = 0,
|
||||
DMA_SLAVE_BUSWIDTH_1_BYTE = 1,
|
||||
@@ -137,11 +146,23 @@ int hal_dma_chan_prep_device(struct aic_dma_chan *chan,
|
||||
u32 p_src,
|
||||
u32 len,
|
||||
enum dma_transfer_direction dir);
|
||||
int hal_dma_prep_mode_device(struct aic_dma_chan *chan,
|
||||
u32 p_dest,
|
||||
u32 p_src,
|
||||
u32 len,
|
||||
enum dma_transfer_direction dir,
|
||||
enum dma_transfer_type transfer_mode);
|
||||
int hal_dma_chan_prep_cyclic(struct aic_dma_chan *chan,
|
||||
u32 p_buf_addr,
|
||||
u32 buf_len,
|
||||
u32 period_len,
|
||||
enum dma_transfer_direction dir);
|
||||
int hal_dma_prep_mode_cyclic(struct aic_dma_chan *chan,
|
||||
u32 p_buf_addr,
|
||||
u32 buf_len,
|
||||
u32 period_len,
|
||||
enum dma_transfer_direction dir,
|
||||
enum dma_transfer_type transfer_mode);
|
||||
enum dma_status hal_dma_chan_tx_status(struct aic_dma_chan *chan, u32 *left_size);
|
||||
int hal_dma_chan_start(struct aic_dma_chan *chan);
|
||||
int hal_dma_chan_stop(struct aic_dma_chan *chan);
|
||||
|
||||
@@ -17,6 +17,7 @@ extern "C" {
|
||||
|
||||
int hal_efuse_init(void);
|
||||
int hal_efuse_deinit(void);
|
||||
int hal_efuse_get_version(void);
|
||||
int hal_efuse_wait_ready(void);
|
||||
int hal_efuse_read(u32 wid, u32 *wval);
|
||||
int hal_efuse_write(u32 wid, u32 wval);
|
||||
|
||||
@@ -11,8 +11,9 @@
|
||||
|
||||
#include "aic_osal.h"
|
||||
|
||||
#define AIC_GPAI_NUM_BITS 12
|
||||
#define AIC_GPAI_TIMEOUT 1000 /* 1000 ms */
|
||||
#define AIC_GPAI_NUM_BITS 12
|
||||
#define AIC_GPAI_TIMEOUT 1000 /* 1000 ms */
|
||||
#define AIC_GPAI_FIFO_MAX_DEPTH 32
|
||||
|
||||
enum aic_gpai_mode {
|
||||
AIC_GPAI_MODE_SINGLE = 0,
|
||||
@@ -26,6 +27,7 @@ enum aic_gpai_obtain_data_mode {
|
||||
};
|
||||
|
||||
typedef void (*dma_callback)(void *dma_param);
|
||||
typedef void (*irq_callback)(void *cb_param);
|
||||
|
||||
struct aic_dma_transfer_info
|
||||
{
|
||||
@@ -38,6 +40,21 @@ struct aic_dma_transfer_info
|
||||
dma_callback callback;
|
||||
};
|
||||
|
||||
struct aic_gpai_irq_info
|
||||
{
|
||||
u32 chan_id;
|
||||
void *callback_param;
|
||||
irq_callback callback;
|
||||
};
|
||||
|
||||
struct aic_gpai_ch_info
|
||||
{
|
||||
u32 chan_id;
|
||||
u16 adc_values[AIC_GPAI_FIFO_MAX_DEPTH];
|
||||
u8 fifo_valid_cnt;
|
||||
enum aic_gpai_mode mode;
|
||||
};
|
||||
|
||||
struct aic_gpai_ch {
|
||||
u8 id;
|
||||
u8 available;
|
||||
@@ -47,6 +64,8 @@ struct aic_gpai_ch {
|
||||
u32 smp_period;
|
||||
u32 pclk_rate;
|
||||
u16 latest_data;
|
||||
u16 fifo_data[AIC_GPAI_FIFO_MAX_DEPTH];
|
||||
u8 fifo_valid_cnt;
|
||||
u8 fifo_depth;
|
||||
u8 fifo_thd;
|
||||
|
||||
@@ -60,6 +79,7 @@ struct aic_gpai_ch {
|
||||
u8 irq_count;
|
||||
u8 dma_port_id;
|
||||
struct aic_dma_transfer_info dma_rx_info;
|
||||
struct aic_gpai_irq_info irq_info;
|
||||
|
||||
aicos_sem_t complete;
|
||||
};
|
||||
@@ -70,7 +90,7 @@ int aich_gpai_ch_init(struct aic_gpai_ch *chan, u32 pclk);
|
||||
|
||||
irqreturn_t aich_gpai_isr(int irq, void *arg);
|
||||
|
||||
int aich_gpai_read(struct aic_gpai_ch *chan, u32 *val, u32 timeout);
|
||||
int aich_gpai_read(struct aic_gpai_ch *chan, u16 *val, u32 timeout);
|
||||
s32 aich_gpai_data2vol(u16 data);
|
||||
|
||||
struct aic_gpai_ch *hal_gpai_ch_is_valid(u32 ch);
|
||||
|
||||
@@ -27,6 +27,47 @@ struct aic_i2c_msg
|
||||
uint8_t *buf;
|
||||
};
|
||||
|
||||
enum aic_msg_status {
|
||||
MSG_IDLE = 0,
|
||||
MSG_IN_PROCESS = 1,
|
||||
};
|
||||
|
||||
struct slave_param
|
||||
{
|
||||
uint32_t cmd;
|
||||
uint8_t *arg;
|
||||
};
|
||||
|
||||
typedef int (*i2c_slave_cb_t) (void *callback_param);
|
||||
|
||||
struct aic_i2c_slave_info
|
||||
{
|
||||
void *callback_param;
|
||||
i2c_slave_cb_t slave_cb;
|
||||
};
|
||||
|
||||
typedef struct aic_i2c_ctrl aic_i2c_ctrl;
|
||||
|
||||
struct aic_i2c_ctrl
|
||||
{
|
||||
int32_t index;
|
||||
char *device_name;
|
||||
unsigned long reg_base;
|
||||
uint32_t addr_bit;
|
||||
uint32_t speed_mode;
|
||||
uint32_t bus_mode;
|
||||
struct aic_i2c_msg *msg;
|
||||
struct aic_i2c_slave_info slave;
|
||||
enum aic_msg_status msg_status;
|
||||
uint32_t slave_addr;
|
||||
uint32_t abort_source;
|
||||
uint32_t msg_err;
|
||||
uint32_t buf_write_idx;
|
||||
uint32_t buf_read_idx;
|
||||
bool is_first_message;
|
||||
bool is_last_message;
|
||||
};
|
||||
|
||||
typedef enum {
|
||||
I2C_OK = 0,
|
||||
I2C_ERR = -1,
|
||||
@@ -35,6 +76,14 @@ typedef enum {
|
||||
I2C_UNSPUPPORTED = -4,
|
||||
} i2c_error_t;
|
||||
|
||||
enum i2c_slave_event {
|
||||
I2C_SLAVE_READ_REQUESTED,
|
||||
I2C_SLAVE_WRITE_REQUESTED,
|
||||
I2C_SLAVE_READ_PROCESSED,
|
||||
I2C_SLAVE_WRITE_RECEIVED,
|
||||
I2C_SLAVE_STOP,
|
||||
};
|
||||
|
||||
#define I2C_DEFALT_CLOCK 24000000
|
||||
|
||||
#define I2C_CTL 0x00
|
||||
@@ -144,281 +193,251 @@ typedef enum {
|
||||
|
||||
#define I2C_ENABLE_MASTER_DISABLE_SLAVE (0x3)
|
||||
|
||||
#define I2C_FIFO_DEPTH 8
|
||||
#define I2C_TXFIFO_THRESHOLD (I2C_FIFO_DEPTH / 2 - 1)
|
||||
#define I2C_RXFIFO_THRESHOLD (I2C_FIFO_DEPTH / 2)
|
||||
#define I2C_FIFO_DEPTH 8
|
||||
#define I2C_TXFIFO_THRESHOLD (I2C_FIFO_DEPTH / 2 - 1)
|
||||
#define I2C_RXFIFO_THRESHOLD 0
|
||||
|
||||
#define I2C_INTR_MASTER_TX_MASK \
|
||||
(I2C_INTR_TX_EMPTY | I2C_INTR_TX_ABRT | I2C_INTR_STOP_DET)
|
||||
#define FS_MIN_SCL_HIGH 600
|
||||
#define FS_MIN_SCL_LOW 1300
|
||||
#define SS_MIN_SCL_HIGH 4200
|
||||
#define SS_MIN_SCL_LOW 5210
|
||||
|
||||
#define I2C_INTR_MASTER_RX_MASK \
|
||||
(I2C_INTR_RX_UNDER | I2C_INTR_RX_FULL | I2C_INTR_STOP_DET)
|
||||
#define I2C_TIMEOUT_DEF_VAL 1000
|
||||
#define I2C_INTR_ERROR_RX 0x0001
|
||||
#define I2C_INTR_ERROR_ABRT 0x0002
|
||||
|
||||
#define I2C_INTR_SLAVE_TX_MASK \
|
||||
(I2C_INTR_RD_REQ | I2C_INTR_RX_DONE | I2C_INTR_STOP_DET)
|
||||
#define I2C_MASTER_MODE 0
|
||||
#define I2C_SLAVE_MODE 1
|
||||
#define I2C_400K_SPEED 0
|
||||
#define I2C_100K_SPEED 1
|
||||
#define I2C_7BIT_ADDR 0
|
||||
#define I2C_10BIT_ADDR 1
|
||||
|
||||
#define I2C_INTR_SLAVE_RX_MASK \
|
||||
(I2C_INTR_RX_FULL | I2C_INTR_RX_UNDER | I2C_INTR_STOP_DET)
|
||||
#define I2C_INTR_MASTER_MASK (I2C_INTR_RX_UNDER |\
|
||||
I2C_INTR_RX_FULL |\
|
||||
I2C_INTR_TX_EMPTY |\
|
||||
I2C_INTR_TX_ABRT |\
|
||||
I2C_INTR_STOP_DET)
|
||||
|
||||
#define FS_MIN_SCL_HIGH 600
|
||||
#define FS_MIN_SCL_LOW 1300
|
||||
#define SS_MIN_SCL_HIGH 4000
|
||||
#define SS_MIN_SCL_LOW 4700
|
||||
#define I2C_INTR_SLAVE_MASK (I2C_INTR_RX_UNDER |\
|
||||
I2C_INTR_RX_FULL |\
|
||||
I2C_INTR_RD_REQ |\
|
||||
I2C_INTR_TX_ABRT |\
|
||||
I2C_INTR_RX_DONE |\
|
||||
I2C_INTR_START_DET)
|
||||
|
||||
#define I2C_TIMEOUT_DEF_VAL 1000
|
||||
|
||||
static inline void aic_i2c_module_enable(unsigned long reg_base)
|
||||
static inline void hal_i2c_module_enable(aic_i2c_ctrl *i2c_dev)
|
||||
{
|
||||
uint32_t reg_val;
|
||||
|
||||
reg_val = readl(reg_base + I2C_ENABLE);
|
||||
reg_val = readl(i2c_dev->reg_base + I2C_ENABLE);
|
||||
reg_val |= I2C_ENABLE_BIT;
|
||||
writel(reg_val, reg_base + I2C_ENABLE);
|
||||
writel(reg_val, i2c_dev->reg_base + I2C_ENABLE);
|
||||
}
|
||||
|
||||
static inline void aic_i2c_module_disable(unsigned long reg_base)
|
||||
static inline void hal_i2c_module_disable(aic_i2c_ctrl *i2c_dev)
|
||||
{
|
||||
uint32_t reg_val;
|
||||
|
||||
writel(0x100, reg_base + I2C_INTR_CLR);
|
||||
reg_val = readl(reg_base + I2C_ENABLE);
|
||||
writel(0x100, i2c_dev->reg_base + I2C_INTR_CLR);
|
||||
reg_val = readl(i2c_dev->reg_base + I2C_ENABLE);
|
||||
reg_val &= ~I2C_ENABLE_BIT;
|
||||
writel(reg_val, reg_base + I2C_ENABLE);
|
||||
writel(reg_val, i2c_dev->reg_base + I2C_ENABLE);
|
||||
}
|
||||
|
||||
static inline unsigned long aic_i2c_module_status(unsigned long reg_base)
|
||||
static inline unsigned long hal_i2c_module_status(aic_i2c_ctrl *i2c_dev)
|
||||
{
|
||||
return readl(reg_base + I2C_ENABLE_STATUS) & 1;
|
||||
return readl(i2c_dev->reg_base + I2C_ENABLE_STATUS) & 1;
|
||||
}
|
||||
|
||||
static inline void aic_i2c_transmit_data(unsigned long reg_base, uint16_t data)
|
||||
static inline void hal_i2c_transmit_data(aic_i2c_ctrl *i2c_dev, uint8_t data)
|
||||
{
|
||||
writel(data, reg_base + I2C_DATA_CMD);
|
||||
writel(data, i2c_dev->reg_base + I2C_DATA_CMD);
|
||||
}
|
||||
|
||||
static inline void aic_i2c_transmit_data_with_cmd(unsigned long reg_base,
|
||||
static inline void hal_i2c_transmit_data_with_cmd(aic_i2c_ctrl *i2c_dev,
|
||||
unsigned long data)
|
||||
{
|
||||
writel(data, reg_base + I2C_DATA_CMD);
|
||||
writel(data, i2c_dev->reg_base + I2C_DATA_CMD);
|
||||
}
|
||||
|
||||
static inline void aic_i2c_transmit_data_with_stop_bit(unsigned long reg_base,
|
||||
static inline void hal_i2c_transmit_data_with_stop_bit(aic_i2c_ctrl *i2c_dev,
|
||||
uint8_t data)
|
||||
{
|
||||
uint32_t reg_val;
|
||||
|
||||
reg_val = I2C_DATA_CMD_STOP | data;
|
||||
writel(reg_val, reg_base + I2C_DATA_CMD);
|
||||
writel(reg_val, i2c_dev->reg_base + I2C_DATA_CMD);
|
||||
}
|
||||
|
||||
static inline unsigned long
|
||||
aic_i2c_get_transmit_fifo_num(unsigned long reg_base)
|
||||
hal_i2c_get_transmit_fifo_num(aic_i2c_ctrl *i2c_dev)
|
||||
{
|
||||
return readl(reg_base + I2C_TXFLR);
|
||||
return readl(i2c_dev->reg_base + I2C_TXFLR);
|
||||
}
|
||||
|
||||
static inline void aic_i2c_transfer_stop_bit(unsigned long reg_base)
|
||||
static inline void hal_i2c_transfer_stop_bit(aic_i2c_ctrl *i2c_dev)
|
||||
{
|
||||
writel(I2C_DATA_CMD_STOP, reg_base + I2C_DATA_CMD);
|
||||
writel(I2C_DATA_CMD_STOP, i2c_dev->reg_base + I2C_DATA_CMD);
|
||||
}
|
||||
|
||||
static inline void aic_i2c_read_data_cmd(unsigned long reg_base)
|
||||
static inline void hal_i2c_read_data_cmd(aic_i2c_ctrl *i2c_dev)
|
||||
{
|
||||
writel(I2C_DATA_CMD_READ, reg_base + I2C_DATA_CMD);
|
||||
writel(I2C_DATA_CMD_READ, i2c_dev->reg_base + I2C_DATA_CMD);
|
||||
}
|
||||
|
||||
static inline void aic_i2c_read_data_cmd_with_stop_bit(unsigned long reg_base)
|
||||
static inline void hal_i2c_read_data_cmd_with_stop_bit(aic_i2c_ctrl *i2c_dev)
|
||||
{
|
||||
writel(I2C_DATA_CMD_READ | I2C_DATA_CMD_STOP, reg_base + I2C_DATA_CMD);
|
||||
writel(I2C_DATA_CMD_READ | I2C_DATA_CMD_STOP, i2c_dev->reg_base + I2C_DATA_CMD);
|
||||
}
|
||||
|
||||
static inline unsigned long aic_i2c_get_receive_fifo_num(unsigned long reg_base)
|
||||
static inline unsigned long hal_i2c_get_receive_fifo_num(aic_i2c_ctrl *i2c_dev)
|
||||
{
|
||||
return readl(reg_base + I2C_RXFLR);
|
||||
return readl(i2c_dev->reg_base + I2C_RXFLR);
|
||||
}
|
||||
|
||||
static inline uint8_t aic_i2c_get_receive_data(unsigned long reg_base)
|
||||
static inline uint8_t hal_i2c_get_receive_data(aic_i2c_ctrl *i2c_dev)
|
||||
{
|
||||
return readb(reg_base + I2C_DATA_CMD);
|
||||
return readb(i2c_dev->reg_base + I2C_DATA_CMD);
|
||||
}
|
||||
|
||||
static inline void
|
||||
aic_i2c_read_data_cmd_with_restart_stop_bit(unsigned long reg_base)
|
||||
hal_i2c_read_data_cmd_with_restart_stop_bit(aic_i2c_ctrl *i2c_dev)
|
||||
{
|
||||
writel(I2C_DATA_CMD_READ | I2C_DATA_CMD_STOP | I2C_DATA_CMD_RESTART,
|
||||
reg_base + I2C_DATA_CMD);
|
||||
i2c_dev->reg_base + I2C_DATA_CMD);
|
||||
}
|
||||
|
||||
static inline void
|
||||
aic_i2c_read_data_cmd_with_restart_bit(unsigned long reg_base)
|
||||
hal_i2c_read_data_cmd_with_restart_bit(aic_i2c_ctrl *i2c_dev)
|
||||
{
|
||||
uint32_t reg_val;
|
||||
|
||||
reg_val = readl(reg_base + I2C_CTL);
|
||||
reg_val = readl(i2c_dev->reg_base + I2C_CTL);
|
||||
reg_val |= I2C_CTL_RESTART_ENABLE;
|
||||
writel(reg_val, reg_base + I2C_CTL);
|
||||
writel(I2C_DATA_CMD_READ | I2C_DATA_CMD_RESTART, reg_base + I2C_DATA_CMD);
|
||||
writel(reg_val, i2c_dev->reg_base + I2C_CTL);
|
||||
writel(I2C_DATA_CMD_READ | I2C_DATA_CMD_RESTART, i2c_dev->reg_base + I2C_DATA_CMD);
|
||||
}
|
||||
|
||||
static inline unsigned long aic_i2c_set_read_cmd(unsigned long reg_val)
|
||||
static inline unsigned long hal_i2c_set_read_cmd(unsigned long reg_val)
|
||||
{
|
||||
return (reg_val | I2C_DATA_CMD_READ);
|
||||
}
|
||||
|
||||
static inline unsigned long aic_i2c_set_stop_bit(unsigned long reg_val)
|
||||
static inline unsigned long hal_i2c_set_stop_bit(unsigned long reg_val)
|
||||
{
|
||||
return (reg_val | I2C_DATA_CMD_STOP);
|
||||
}
|
||||
|
||||
static inline unsigned long aic_i2c_set_restart_bit(unsigned long reg_val)
|
||||
static inline unsigned long hal_i2c_set_restart_bit(unsigned long reg_val)
|
||||
{
|
||||
return (reg_val | I2C_DATA_CMD_RESTART);
|
||||
}
|
||||
|
||||
static inline void aic_i2c_set_restart_bit_with_data(unsigned long reg_base,
|
||||
static inline void hal_i2c_set_restart_bit_with_data(aic_i2c_ctrl *i2c_dev,
|
||||
uint8_t data)
|
||||
{
|
||||
uint32_t reg_val;
|
||||
|
||||
reg_val = readl(reg_base + I2C_CTL);
|
||||
reg_val = readl(i2c_dev->reg_base + I2C_CTL);
|
||||
reg_val |= I2C_CTL_RESTART_ENABLE;
|
||||
writel(reg_val, reg_base + I2C_CTL);
|
||||
writel(data | I2C_DATA_CMD_RESTART, reg_base + I2C_DATA_CMD);
|
||||
writel(reg_val, i2c_dev->reg_base + I2C_CTL);
|
||||
writel(data | I2C_DATA_CMD_RESTART, i2c_dev->reg_base + I2C_DATA_CMD);
|
||||
}
|
||||
|
||||
static inline unsigned long
|
||||
aic_i2c_get_raw_interrupt_state(unsigned long reg_base)
|
||||
hal_i2c_get_raw_interrupt_state(aic_i2c_ctrl *i2c_dev)
|
||||
{
|
||||
return readl(reg_base + I2C_INTR_RAW_STAT);
|
||||
return readl(i2c_dev->reg_base + I2C_INTR_RAW_STAT);
|
||||
}
|
||||
|
||||
static inline unsigned long aic_i2c_get_interrupt_state(unsigned long reg_base)
|
||||
static inline unsigned long hal_i2c_get_interrupt_state(aic_i2c_ctrl *i2c_dev)
|
||||
{
|
||||
return readl(reg_base + I2C_INTR_CLR);
|
||||
return readl(i2c_dev->reg_base + I2C_INTR_CLR);
|
||||
}
|
||||
|
||||
static inline void aic_i2c_disable_all_irq(unsigned long reg_base)
|
||||
static inline void hal_i2c_disable_all_irq(aic_i2c_ctrl *i2c_dev)
|
||||
{
|
||||
writel(0, reg_base + I2C_INTR_MASK);
|
||||
writel(0, i2c_dev->reg_base + I2C_INTR_MASK);
|
||||
}
|
||||
|
||||
static inline void aic_i2c_clear_irq_flags(unsigned long reg_base,
|
||||
static inline void hal_i2c_clear_irq_flags(aic_i2c_ctrl *i2c_dev,
|
||||
unsigned long flags)
|
||||
{
|
||||
writel(flags, reg_base + I2C_INTR_CLR);
|
||||
writel(flags, i2c_dev->reg_base + I2C_INTR_CLR);
|
||||
}
|
||||
|
||||
static inline void aic_i2c_clear_all_irq_flags(unsigned long reg_base)
|
||||
static inline void hal_i2c_clear_all_irq_flags(aic_i2c_ctrl *i2c_dev)
|
||||
{
|
||||
writel(0xffff, reg_base + I2C_INTR_CLR);
|
||||
writel(0xffff, i2c_dev->reg_base + I2C_INTR_CLR);
|
||||
}
|
||||
|
||||
static inline void aic_i2c_clear_rx_full_flag(unsigned long reg_base)
|
||||
static inline void hal_i2c_clear_rx_full_flag(aic_i2c_ctrl *i2c_dev)
|
||||
{
|
||||
writel(I2C_INTR_RX_FULL, reg_base + I2C_INTR_CLR);
|
||||
writel(I2C_INTR_RX_FULL, i2c_dev->reg_base + I2C_INTR_CLR);
|
||||
}
|
||||
|
||||
static inline void aic_i2c_clear_tx_empty_flag(unsigned long reg_base)
|
||||
static inline void hal_i2c_clear_tx_empty_flag(aic_i2c_ctrl *i2c_dev)
|
||||
{
|
||||
writel(I2C_INTR_TX_EMPTY, reg_base + I2C_INTR_CLR);
|
||||
writel(I2C_INTR_TX_EMPTY, i2c_dev->reg_base + I2C_INTR_CLR);
|
||||
}
|
||||
|
||||
static inline void aic_i2c_master_enable_transmit_irq(unsigned long reg_base)
|
||||
static inline void hal_i2c_master_enable_irq(aic_i2c_ctrl *i2c_dev)
|
||||
{
|
||||
writel(I2C_INTR_MASTER_TX_MASK, reg_base + I2C_INTR_MASK);
|
||||
writel(I2C_INTR_MASTER_MASK, i2c_dev->reg_base + I2C_INTR_MASK);
|
||||
}
|
||||
|
||||
static inline void aic_i2c_master_enable_receive_irq(unsigned long reg_base)
|
||||
static inline void hal_i2c_slave_enable_irq(aic_i2c_ctrl *i2c_dev)
|
||||
{
|
||||
writel(I2C_INTR_MASTER_RX_MASK, reg_base + I2C_INTR_MASK);
|
||||
writel(I2C_INTR_SLAVE_MASK, i2c_dev->reg_base + I2C_INTR_MASK);
|
||||
}
|
||||
|
||||
static inline void aic_i2c_slave_enable_transmit_irq(unsigned long reg_base)
|
||||
static inline void hal_i2c_set_transmit_fifo_threshold(aic_i2c_ctrl *i2c_dev)
|
||||
{
|
||||
writel(I2C_INTR_SLAVE_TX_MASK, reg_base + I2C_INTR_MASK);
|
||||
writel(I2C_TXFIFO_THRESHOLD, i2c_dev->reg_base + I2C_TX_TL);
|
||||
}
|
||||
|
||||
static inline void aic_i2c_slave_enable_receive_irq(unsigned long reg_base)
|
||||
{
|
||||
writel(I2C_INTR_SLAVE_RX_MASK, reg_base + I2C_INTR_MASK);
|
||||
}
|
||||
|
||||
static inline void aic_i2c_set_transmit_fifo_threshold(unsigned long reg_base)
|
||||
{
|
||||
writel(I2C_TXFIFO_THRESHOLD, reg_base + I2C_TX_TL);
|
||||
}
|
||||
|
||||
static inline void aic_i2c_set_receive_fifo_threshold(unsigned long reg_base,
|
||||
static inline void hal_i2c_set_receive_fifo_threshold(aic_i2c_ctrl *i2c_dev,
|
||||
uint8_t level)
|
||||
{
|
||||
writel(level - 1, reg_base + I2C_RX_TL);
|
||||
writel(level - 1, i2c_dev->reg_base + I2C_RX_TL);
|
||||
}
|
||||
|
||||
/**
|
||||
\brief I2C initialization: clock enable and release reset signal
|
||||
\param[in] i2c_idx i2c index number
|
||||
\return 0, if success, error code if failed
|
||||
*/
|
||||
int aic_i2c_init(int32_t i2c_idx);
|
||||
static inline void hal_i2c_config_fifo_slave(aic_i2c_ctrl *i2c_dev)
|
||||
{
|
||||
writel(0, i2c_dev->reg_base + I2C_TX_TL);
|
||||
writel(0, i2c_dev->reg_base + I2C_RX_TL);
|
||||
}
|
||||
|
||||
static inline int hal_i2c_bus_status(aic_i2c_ctrl *i2c_dev)
|
||||
{
|
||||
uint32_t status;
|
||||
|
||||
status = (readl(i2c_dev->reg_base + I2C_STATUS) & I2C_STATUS_ACTIVITY);
|
||||
return status;
|
||||
}
|
||||
|
||||
static inline void hal_i2c_flags_mask(aic_i2c_ctrl *i2c_dev, unsigned long flags)
|
||||
{
|
||||
writel(flags, i2c_dev->reg_base + I2C_INTR_MASK);
|
||||
}
|
||||
|
||||
|
||||
void hal_i2c_set_hold(unsigned long reg_base, u32 val);
|
||||
|
||||
/**
|
||||
\brief Configure i2c master mode or slave mode
|
||||
\param[in] reg_base iic controller register base
|
||||
\param[in] mode if true, master mode; if false, slave mode
|
||||
\return 0, if success, error code if failed
|
||||
*/
|
||||
int aic_i2c_set_master_slave_mode(unsigned long reg_base, uint8_t mode);
|
||||
|
||||
/**
|
||||
\brief Configure i2c master address mode
|
||||
\param[in] reg_base iic controller register base
|
||||
\param[in] enable if true, 10bit address mode;
|
||||
if false, 7bit address mode
|
||||
\return 0, if success, error code if failed
|
||||
*/
|
||||
int aic_i2c_master_10bit_addr(unsigned long reg_base, uint8_t enable);
|
||||
|
||||
/**
|
||||
\brief Configure i2c slave address mode
|
||||
\param[in] reg_base iic controller register base
|
||||
\param[in] enable if true, 10bit address mode;
|
||||
if false, 7bit address mode
|
||||
\return 0, if success, error code if failed
|
||||
*/
|
||||
int aic_i2c_slave_10bit_addr(unsigned long reg_base, uint8_t enable);
|
||||
|
||||
/**
|
||||
\brief Configure i2c speed mode
|
||||
\param[in] reg_base iic controller register base
|
||||
\param[in] mode if true, fast mode; if false, standard mode
|
||||
\return 0, if success, error code if failed
|
||||
*/
|
||||
int aic_i2c_speed_mode_select(unsigned long reg_base, uint32_t clk_freq,
|
||||
uint8_t mode);
|
||||
|
||||
/**
|
||||
\brief Configure target device address
|
||||
\param[in] reg_base iic controller register base
|
||||
\param[in] addr target address
|
||||
\return 0, if success, error code if failed
|
||||
*/
|
||||
void aic_i2c_target_addr(unsigned long reg_base, uint32_t addr);
|
||||
|
||||
/**
|
||||
\brief Configure i2c own address in slave mode
|
||||
\param[in] reg_base iic controller register base
|
||||
\param[in] addr i2c own address
|
||||
\return 0, if success, error code if failed
|
||||
*/
|
||||
int aic_i2c_slave_own_addr(unsigned long reg_base, uint32_t addr);
|
||||
|
||||
int32_t aic_i2c_master_send_msg(unsigned long reg_base,
|
||||
int hal_i2c_init(aic_i2c_ctrl *i2c_dev);
|
||||
int hal_i2c_clk_init(aic_i2c_ctrl *i2c_dev);
|
||||
int hal_i2c_set_master_slave_mode(aic_i2c_ctrl *i2c_dev);
|
||||
int hal_i2c_master_10bit_addr(aic_i2c_ctrl *i2c_dev);
|
||||
int hal_i2c_slave_10bit_addr(aic_i2c_ctrl *i2c_dev);
|
||||
int hal_i2c_slave_own_addr(aic_i2c_ctrl *i2c_dev, uint32_t addr);
|
||||
void hal_i2c_target_addr(aic_i2c_ctrl *i2c_dev, uint32_t addr);
|
||||
void hal_i2c_set_hold(aic_i2c_ctrl *i2c_dev, u32 val);
|
||||
int hal_i2c_speed_mode_select(aic_i2c_ctrl *i2c_dev,
|
||||
uint32_t clk_freq, uint8_t mode);
|
||||
int32_t hal_i2c_wait_bus_free(aic_i2c_ctrl *i2c_dev, uint32_t timeout);
|
||||
int32_t hal_i2c_master_send_msg(aic_i2c_ctrl *i2c_dev,
|
||||
struct aic_i2c_msg *msg, uint8_t is_last_message);
|
||||
int32_t hal_i2c_master_receive_msg(aic_i2c_ctrl *i2c_dev,
|
||||
struct aic_i2c_msg *msg, uint8_t is_last_message);
|
||||
int32_t aic_i2c_master_receive_msg(unsigned long reg_base,
|
||||
struct aic_i2c_msg *msg, uint8_t is_last_message);
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
|
||||
@@ -32,8 +32,8 @@ extern "C" {
|
||||
#define HAL_QSPI_RX_FIFO 0
|
||||
#define HAL_QSPI_TX_FIFO 1
|
||||
|
||||
#define HAL_QSPI_WAIT_30_US 30
|
||||
#define HAL_QSPI_WAIT_PER_CYCLE HAL_QSPI_WAIT_30_US
|
||||
#define HAL_QSPI_WAIT_DELAY_US 1
|
||||
#define HAL_QSPI_WAIT_PER_CYCLE HAL_QSPI_WAIT_DELAY_US
|
||||
#define HAL_QSPI_DMA_DEV_MAXBURST 8
|
||||
#define HAL_QSPI_DMA_MEM_MAXBURST 16
|
||||
#define HAL_QSPI_DMA_4BYTES_LINE 4
|
||||
|
||||
@@ -19,6 +19,17 @@ enum aic_tsen_mode {
|
||||
AIC_TSEN_MODE_PERIOD = 1
|
||||
};
|
||||
|
||||
enum aic_tsen_soft_mode {
|
||||
AIC_TSEN_SOFT_MODE_SINGLE = 0,
|
||||
AIC_TSEN_SOFT_MODE_PERIOD = 1,
|
||||
AIC_TSEN_SOFT_MODE_POLLING = 2
|
||||
};
|
||||
|
||||
enum aic_tsen_sensor {
|
||||
AIC_TSEN_SENSOR_CPU = 0,
|
||||
AIC_TSEN_SENSOR_GPAI = 1
|
||||
};
|
||||
|
||||
#define AIC_TSEN_USE_DIFFERENT_MODE 1
|
||||
#define AIC_TSEN_USE_INVERTED 1
|
||||
|
||||
@@ -27,6 +38,7 @@ struct aic_tsen_ch {
|
||||
bool available;
|
||||
char name[16];
|
||||
enum aic_tsen_mode mode;
|
||||
enum aic_tsen_soft_mode soft_mode;
|
||||
bool diff_mode;
|
||||
bool inverted;
|
||||
u16 latest_data; // 10 * actual temperature value
|
||||
@@ -61,5 +73,7 @@ irqreturn_t hal_tsen_irq_handle(int irq, void *arg);
|
||||
s32 hal_tsen_clk_init(void);
|
||||
void hal_tsen_pclk_get(struct aic_tsen_ch *chan);
|
||||
void hal_tsen_curve_fitting(struct aic_tsen_ch *chan);
|
||||
void hal_tsen_set_ch_num(u32 num);
|
||||
struct aic_tsen_ch *hal_tsen_get_valid_ch(u32 ch);
|
||||
|
||||
#endif // end of _ARTINCHIP_HAL_TSEN_H_
|
||||
|
||||
@@ -28,6 +28,7 @@ enum aic_warm_reset_type {
|
||||
enum aic_warm_reset_type {
|
||||
WRI_TYPE_VDD11_SP_POR = 0,
|
||||
WRI_TYPE_VDD11_SW_POR,
|
||||
WRI_TYPE_VDD11_C908_POR,
|
||||
WRI_TYPE_RTC_POR,
|
||||
WRI_TYPE_PIN_RST,
|
||||
WRI_TYPE_THS_RST,
|
||||
@@ -53,5 +54,6 @@ enum aic_warm_reset_type {
|
||||
enum aic_warm_reset_type aic_wr_type_get(void);
|
||||
enum aic_reboot_reason aic_judge_reboot_reason(enum aic_warm_reset_type hw,
|
||||
u32 sw);
|
||||
void aic_clr_reboot_reason(void);
|
||||
|
||||
#endif
|
||||
|
||||
Reference in New Issue
Block a user