Go to the documentation of this file.
24 #include "picovoice.h"
27 #define PV_SAI_CHANNEL (0)
28 #define PV_SAI_IRQ (SAI1_IRQn)
29 #define PV_SAITxIRQHandler (SAI1_IRQHandler)
30 #define PV_SAI_TX_SYNC_MODE (kSAI_ModeAsync)
31 #define PV_SAI_RX_SYNC_MODE (kSAI_ModeSync)
32 #define PV_SAI_MCLK_OUTPUT (true)
33 #define PV_SAI_MASTER_SLAVE (kSAI_Master)
34 #define PV_SAI1_CLOCK_SOURCE_SELECT (2U)
35 #define PV_SAI1_CLOCK_SOURCE_PRE_DIVIDER (0U)
36 #define PV_SAI1_CLOCK_SOURCE_DIVIDER (63U)
37 #define PV_SAI_CLK_FREQ \
38 (CLOCK_GetFreq(kCLOCK_AudioPllClk) / (PV_SAI1_CLOCK_SOURCE_DIVIDER + 1U) / \
39 (PV_SAI1_CLOCK_SOURCE_PRE_DIVIDER + 1U))
40 #define PV_SAI_TX_IRQ (SAI1_IRQn)
41 #define PV_SAI_RX_IRQ (SAI1_IRQn)
43 #define PV_I2C (LPI2C1)
44 #define PV_LPI2C_CLOCK_SOURCE_SELECT (0U)
45 #define PV_LPI2C_CLOCK_SOURCE_DIVIDER (5U)
46 #define PV_I2C_CLK_FREQ ((CLOCK_GetFreq(kCLOCK_Usb1PllClk) / 8) / (PV_LPI2C_CLOCK_SOURCE_DIVIDER + 1U))
48 #define PV_AUDIO_REC_AUDIO_FREQUENCY (kSAI_SampleRate16KHz)
49 #define PV_AUDIO_REC_CHANNEL_NUMBER (2U)
50 #define PV_AUDIO_REC_RECORD_BUFFER_SIZE (512U)
51 #define PV_AUDIO_REC_BIT_WIDTH (kSAI_WordWidth16bits)
52 #define PV_AUDIO_REC_MASTER_CLOCK (PV_SAI_CLK_FREQ)
53 #define AUDIO_IN_PCM_BUFFER_SIZE_INT16 ((uint32_t)(PV_AUDIO_REC_AUDIO_FREQUENCY / 1000 \
54 * PV_AUDIO_REC_CHANNEL_NUMBER))
55 #define AUDIO_IN_PCM_BUFFER_SIZE_INT8 (2 * AUDIO_IN_PCM_BUFFER_SIZE_INT16)
56 #define PV_AUDIO_REC_RECORD_BUFFER_NUMBER (2U)
59 #define PV_DMAMUX (DMAMUX)
60 #define PV_TX_EDMA_CHANNEL (0U)
61 #define PV_RX_EDMA_CHANNEL (1U)
62 #define PV_SAI_TX_SOURCE (kDmaRequestMuxSai1Tx)
63 #define PV_SAI_RX_SOURCE (kDmaRequestMuxSai1Rx)
135 .master_slave =
false,
#define PV_SAI_TX_SYNC_MODE
static edma_handle_t dmaRxHandle
eDMA transfer handle structure
pv_status_t pv_audio_rec_start(void)
static int16_t ping_pong_buffer[2][PV_AUDIO_REC_RECORD_BUFFER_SIZE]
#define WM8960_I2C_ADDR
WM8960 I2C address.
static void DMAMUX_EnableChannel(DMAMUX_Type *base, uint32_t channel)
Enables the DMAMUX channel.
Initialize structure of the codec.
@ PV_STATUS_INVALID_STATE
#define PV_SAI_MASTER_SLAVE
#define PV_SAI1_CLOCK_SOURCE_SELECT
#define PV_AUDIO_REC_MASTER_CLOCK
void SAI_TransferRxSetConfigEDMA(I2S_Type *base, sai_edma_handle_t *handle, sai_transceiver_t *saiConfig)
Configures the SAI Rx.
SAI DMA transfer handle, users should not touch the content of the handle.
const int16_t * pv_audio_rec_get_new_buffer(void)
#define PV_AUDIO_REC_RECORD_BUFFER_SIZE
#define PV_AUDIO_REC_RECORD_BUFFER_NUMBER
static void BOARD_EnableSaiMclkOutput(bool enable)
#define AUDIO_IN_PCM_BUFFER_SIZE_INT16
sai_master_slave_t masterSlave
codec_i2c_config_t i2cConfig
void SAI_TxSetBitClockRate(I2S_Type *base, uint32_t sourceClockHz, uint32_t sampleRate, uint32_t bitWidth, uint32_t channelNumbers)
Transmitter bit clock rate configurations.
void CLOCK_InitAudioPll(const clock_audio_pll_config_t *config)
Initializes the Audio PLL.
status_t CODEC_Init(codec_handle_t *handle, codec_config_t *config)
Codec initilization.
static codec_handle_t codecHandle
#define BOARD_CODEC_I2C_CLOCK_FREQ
#define PV_AUDIO_REC_AUDIO_FREQUENCY
static int32_t last_read_index
#define IOMUXC_GPR_GPR1_SAI1_MCLK_DIR_MASK
void SAI_TransferRxCreateHandleEDMA(I2S_Type *base, sai_edma_handle_t *handle, sai_edma_callback_t callback, void *userData, edma_handle_t *rxDmaHandle)
Initializes the SAI Rx eDMA handle.
static void rx_callback(I2S_Type *base, sai_edma_handle_t *handle, status_t status, void *userData)
#define PV_LPI2C_CLOCK_SOURCE_DIVIDER
PLL configuration for AUDIO and VIDEO.
static void CLOCK_SetMux(clock_mux_t mux, uint32_t value)
Set CCM MUX node to certain value.
void DMAMUX_Init(DMAMUX_Type *base)
Initializes the DMAMUX peripheral.
void EDMA_GetDefaultConfig(edma_config_t *config)
Gets the eDMA default configuration structure.
static volatile int32_t buffer_index
static volatile int32_t read_index
uint32_t record_buffer_size
sai transceiver configurations
@ kWM8960_InputDifferentialMicInput2
void EDMA_CreateHandle(edma_handle_t *handle, DMA_Type *base, uint32_t channel)
Creates the eDMA handle.
void EDMA_Init(DMA_Type *base, const edma_config_t *config)
Initializes the eDMA peripheral.
Initialize structure of WM8960.
AT_NONCACHEABLE_SECTION_INIT(static sai_edma_handle_t txHandle)
static void CLOCK_SetDiv(clock_div_t divider, uint32_t value)
Set CCM DIV node to certain value.
#define PV_SAI1_CLOCK_SOURCE_PRE_DIVIDER
static sai_transfer_t buffer_config
uint8_t * record_pcm_buffer
static void DMAMUX_SetSource(DMAMUX_Type *base, uint32_t channel, uint32_t source)
Configures the DMAMUX channel source.
pv_status_t pv_audio_rec_init(void)
pv_status_t pv_audio_rec_stop(void)
@ kWM8960_AudioBitWidth16bit
#define AUDIO_IN_PCM_BUFFER_SIZE_INT8
#define PV_SAI_RX_SYNC_MODE
void pv_audio_rec_deinit(void)
#define PV_AUDIO_REC_BIT_WIDTH
eDMA global configuration structure.
#define BOARD_CODEC_I2C_INSTANCE
AT_NONCACHEABLE_SECTION_ALIGN(static uint8_t record_pcm_buffer[AUDIO_IN_PCM_BUFFER_SIZE_INT8], 16)
void SAI_TransferTxSetConfigEDMA(I2S_Type *base, sai_edma_handle_t *handle, sai_transceiver_t *saiConfig)
Configures the SAI Tx.
static edma_config_t dmaConfig
uint32_t codecI2CInstance
#define PV_AUDIO_REC_CHANNEL_NUMBER
void SAI_RxSetBitClockRate(I2S_Type *base, uint32_t sourceClockHz, uint32_t sampleRate, uint32_t bitWidth, uint32_t channelNumbers)
Receiver bit clock rate configurations.
static sai_transceiver_t config
#define PV_RX_EDMA_CHANNEL
@ kWM8960_AudioSampleRate16KHz
status_t SAI_TransferReceiveEDMA(I2S_Type *base, sai_edma_handle_t *handle, sai_transfer_t *xfer)
Performs a non-blocking SAI receive using eDMA.
int32_t status_t
Type used for all status and error return values.
static volatile int32_t write_index
#define PV_SAI1_CLOCK_SOURCE_DIVIDER
void SAI_GetClassicI2SConfig(sai_transceiver_t *config, sai_word_width_t bitWidth, sai_mono_stereo_t mode, uint32_t saiChannelMask)
Get classic I2S mode configurations.
#define PV_LPI2C_CLOCK_SOURCE_SELECT
void SAI_Init(I2S_Type *base)
Initializes the SAI peripheral.