Prvni ulozeni z chegewara githubu
This commit is contained in:
0
libraries/I2S/examples/ADCPlotter/.skip.esp32c3
Normal file
0
libraries/I2S/examples/ADCPlotter/.skip.esp32c3
Normal file
86
libraries/I2S/examples/ADCPlotter/ADCPlotter.ino
Normal file
86
libraries/I2S/examples/ADCPlotter/ADCPlotter.ino
Normal file
@ -0,0 +1,86 @@
|
||||
/*
|
||||
This example is only for ESP devices.
|
||||
|
||||
This example demonstrates usage of integrated Digital to Analog Converter (DAC)
|
||||
You can display sound wave from audio device, or just measure voltage.
|
||||
|
||||
To display audio prepare circuit found in following link or drafted as ASCII art
|
||||
https://forum.arduino.cc/index.php?topic=567581.0
|
||||
(!) Note that unlike in the link we are connecting the supply line to 3.3V (not 5V)
|
||||
because ADC can measure only up to around 3V. Anything above 3V will be very inaccurate.
|
||||
|
||||
^ +3.3V
|
||||
|
|
||||
_
|
||||
| |10k
|
||||
|_|
|
||||
| | |10uF
|
||||
GPIO34-------------*------------| |----------- line in
|
||||
(Default ADC pin) | +| |
|
||||
|
|
||||
_
|
||||
| |10k
|
||||
|_|
|
||||
|
|
||||
|
|
||||
V GND
|
||||
|
||||
Connect hot wire of your audio to Line in and GNd wire of audio cable to common ground (GND)
|
||||
|
||||
Second option to measure voltage on trimmer / potentiometer has following connection
|
||||
^ +3.3V
|
||||
|
|
||||
_
|
||||
| |
|
||||
GPIO34----------->| |
|
||||
(Default ADC pin) |_|
|
||||
|
|
||||
|
|
||||
_
|
||||
| | optional resistor
|
||||
|_|
|
||||
|
|
||||
|
|
||||
V GND
|
||||
Optional resistor will decrease read value.
|
||||
|
||||
Steps to run:
|
||||
1. Select target board:
|
||||
Tools -> Board -> ESP32 Arduino -> your board
|
||||
2. Upload sketch
|
||||
Press upload button (arrow in top left corner)
|
||||
When you see in console line like this: "Connecting........_____.....__"
|
||||
On your board press and hold Boot button and press EN button shortly. Now you can release both buttons.
|
||||
You should see lines like this: "Writing at 0x00010000... (12 %)" with rising percentage on each line.
|
||||
If this fails, try the board buttons right after pressing upload button, or reconnect the USB cable.
|
||||
3. Open plotter
|
||||
Tools -> Serial Plotter
|
||||
Enjoy
|
||||
|
||||
Created by Tomas Pilny
|
||||
on 17th June 2021
|
||||
*/
|
||||
|
||||
#include <I2S.h>
|
||||
|
||||
void setup() {
|
||||
// Open serial communications and wait for port to open:
|
||||
// A baud rate of 115200 is used instead of 9600 for a faster data rate
|
||||
// on non-native USB ports
|
||||
Serial.begin(115200);
|
||||
while (!Serial) {
|
||||
; // wait for serial port to connect. Needed for native USB port only
|
||||
}
|
||||
|
||||
// start I2S at 8 kHz with 32-bits per sample
|
||||
if (!I2S.begin(ADC_DAC_MODE, 8000, 16)) {
|
||||
Serial.println("Failed to initialize I2S!");
|
||||
while (1); // do nothing
|
||||
}
|
||||
}
|
||||
|
||||
void loop() {
|
||||
// read a sample
|
||||
int sample = I2S.read();
|
||||
Serial.println(sample);
|
||||
}
|
0
libraries/I2S/examples/FullDuplex/.skip.esp32c3
Normal file
0
libraries/I2S/examples/FullDuplex/.skip.esp32c3
Normal file
59
libraries/I2S/examples/FullDuplex/FullDuplex.ino
Normal file
59
libraries/I2S/examples/FullDuplex/FullDuplex.ino
Normal file
@ -0,0 +1,59 @@
|
||||
/*
|
||||
This example is only for ESP
|
||||
This example demonstrates simultaneous usage of microphone and speaker using single I2S module.
|
||||
The application transfers data from input to output
|
||||
|
||||
Circuit:
|
||||
* ESP32
|
||||
* GND connected GND
|
||||
* VIN connected 5V
|
||||
* SCK 5
|
||||
* FS 25
|
||||
* DIN 35
|
||||
* DOUT 26
|
||||
* I2S microphone
|
||||
* I2S decoder + headphones / speaker
|
||||
|
||||
created 8 October 2021
|
||||
by Tomas Pilny
|
||||
*/
|
||||
|
||||
#include <I2S.h>
|
||||
const long sampleRate = 16000;
|
||||
const int bitsPerSample = 32;
|
||||
uint8_t *buffer;
|
||||
|
||||
void setup() {
|
||||
Serial.begin(115200);
|
||||
//I2S.setAllPins(5, 25, 35, 26); // you can change default pins; order of pins = (CLK, WS, IN, OUT)
|
||||
if(!I2S.setDuplex()){
|
||||
Serial.println("ERROR - could not set duplex");
|
||||
while(true){
|
||||
vTaskDelay(10); // Cannot continue
|
||||
}
|
||||
}
|
||||
if (!I2S.begin(I2S_PHILIPS_MODE, sampleRate, bitsPerSample)) {
|
||||
Serial.println("Failed to initialize I2S!");
|
||||
while(true){
|
||||
vTaskDelay(10); // Cannot continue
|
||||
}
|
||||
}
|
||||
buffer = (uint8_t*) malloc(I2S.getBufferSize() * (bitsPerSample / 8));
|
||||
if(buffer == NULL){
|
||||
Serial.println("Failed to allocate buffer!");
|
||||
while(true){
|
||||
vTaskDelay(10); // Cannot continue
|
||||
}
|
||||
}
|
||||
Serial.println("Setup done");
|
||||
}
|
||||
|
||||
void loop() {
|
||||
//I2S.write(I2S.read()); // primitive implementation sample-by-sample
|
||||
|
||||
// Buffer based implementation
|
||||
I2S.read(buffer, I2S.getBufferSize() * (bitsPerSample / 8));
|
||||
I2S.write(buffer, I2S.getBufferSize() * (bitsPerSample / 8));
|
||||
|
||||
//optimistic_yield(1000); // yield if last yield occurred before <parameter> CPU clock cycles ago
|
||||
}
|
@ -0,0 +1,44 @@
|
||||
/*
|
||||
This example reads audio data from an Invensense's ICS43432 I2S microphone
|
||||
breakout board, and prints out the samples to the Serial console. The
|
||||
Serial Plotter built into the Arduino IDE can be used to plot the audio
|
||||
data (Tools -> Serial Plotter)
|
||||
|
||||
Circuit:
|
||||
* Arduino/Genuino Zero, MKR family and Nano 33 IoT
|
||||
* ICS43432:
|
||||
* GND connected GND
|
||||
* 3.3V connected to 3.3V (Zero, Nano, ESP32), VCC (MKR)
|
||||
* WS connected to pin 0 (Zero) or 3 (MKR), A2 (Nano) or 25 (ESP32)
|
||||
* CLK connected to pin 1 (Zero) or 2 (MKR), A3 (Nano) or 5 (ESP32)
|
||||
* SD connected to pin 9 (Zero) or A6 (MKR), 4 (Nano) or 26 (ESP32)
|
||||
created 17 November 2016
|
||||
by Sandeep Mistry
|
||||
*/
|
||||
|
||||
#include <I2S.h>
|
||||
|
||||
void setup() {
|
||||
// Open serial communications and wait for port to open:
|
||||
// A baud rate of 115200 is used instead of 9600 for a faster data rate
|
||||
// on non-native USB ports
|
||||
Serial.begin(115200);
|
||||
while (!Serial) {
|
||||
; // wait for serial port to connect. Needed for native USB port only
|
||||
}
|
||||
|
||||
// start I2S at 8 kHz with 32-bits per sample
|
||||
if (!I2S.begin(I2S_PHILIPS_MODE, 8000, 32)) {
|
||||
Serial.println("Failed to initialize I2S!");
|
||||
while (1); // do nothing
|
||||
}
|
||||
}
|
||||
|
||||
void loop() {
|
||||
// read a sample
|
||||
int sample = I2S.read();
|
||||
|
||||
if (sample && sample != -1 && sample != 1) {
|
||||
Serial.println(sample);
|
||||
}
|
||||
}
|
0
libraries/I2S/examples/SimpleTone/.skip.esp32c3
Normal file
0
libraries/I2S/examples/SimpleTone/.skip.esp32c3
Normal file
79
libraries/I2S/examples/SimpleTone/SimpleTone.ino
Normal file
79
libraries/I2S/examples/SimpleTone/SimpleTone.ino
Normal file
@ -0,0 +1,79 @@
|
||||
/*
|
||||
This example generates a square wave based tone at a specified frequency
|
||||
and sample rate. Then outputs the data using the I2S interface to a
|
||||
MAX08357 I2S Amp Breakout board.
|
||||
|
||||
I2S Circuit:
|
||||
* Arduino/Genuino Zero, MKR family and Nano 33 IoT
|
||||
* MAX08357:
|
||||
* GND connected GND
|
||||
* VIN connected 5V
|
||||
* LRC connected to pin 0 (Zero) or 3 (MKR), A2 (Nano) or 25 (ESP32)
|
||||
* BCLK connected to pin 1 (Zero) or 2 (MKR), A3 (Nano) or 5 (ESP32)
|
||||
* DIN connected to pin 9 (Zero) or A6 (MKR), 4 (Nano) or 26 (ESP32)
|
||||
|
||||
DAC Circuit:
|
||||
* ESP32 or ESP32-S2
|
||||
* Audio amplifier
|
||||
- Note:
|
||||
- ESP32 has DAC on GPIO pins 25 and 26.
|
||||
- ESP32-S2 has DAC on GPIO pins 17 and 18.
|
||||
- Connect speaker(s) or headphones.
|
||||
|
||||
created 17 November 2016
|
||||
by Sandeep Mistry
|
||||
For ESP extended
|
||||
Tomas Pilny
|
||||
2nd September 2021
|
||||
*/
|
||||
|
||||
#include <I2S.h>
|
||||
const int frequency = 440; // frequency of square wave in Hz
|
||||
const int amplitude = 500; // amplitude of square wave
|
||||
const int sampleRate = 8000; // sample rate in Hz
|
||||
const int bps = 16;
|
||||
|
||||
const int halfWavelength = (sampleRate / frequency); // half wavelength of square wave
|
||||
|
||||
short sample = amplitude; // current sample value
|
||||
int count = 0;
|
||||
|
||||
i2s_mode_t mode = I2S_PHILIPS_MODE; // I2S decoder is needed
|
||||
// i2s_mode_t mode = ADC_DAC_MODE; // Audio amplifier is needed
|
||||
|
||||
// Mono channel input
|
||||
// This is ESP specific implementation -
|
||||
// samples will be automatically copied to both channels inside I2S driver
|
||||
// If you want to have true mono output use I2S_PHILIPS_MODE and interlay
|
||||
// second channel with 0-value samples.
|
||||
// The order of channels is RIGH followed by LEFT
|
||||
//i2s_mode_t mode = I2S_RIGHT_JUSTIFIED_MODE; // I2S decoder is needed
|
||||
|
||||
void setup() {
|
||||
Serial.begin(115200);
|
||||
Serial.println("I2S simple tone");
|
||||
|
||||
// start I2S at the sample rate with 16-bits per sample
|
||||
if (!I2S.begin(mode, sampleRate, bps)) {
|
||||
Serial.println("Failed to initialize I2S!");
|
||||
while (1); // do nothing
|
||||
}
|
||||
}
|
||||
|
||||
void loop() {
|
||||
if (count % halfWavelength == 0 ) {
|
||||
// invert the sample every half wavelength count multiple to generate square wave
|
||||
sample = -1 * sample;
|
||||
}
|
||||
|
||||
if(mode == I2S_PHILIPS_MODE || mode == ADC_DAC_MODE){ // write the same sample twice, once for Right and once for Left channel
|
||||
I2S.write(sample); // Right channel
|
||||
I2S.write(sample); // Left channel
|
||||
}else if(mode == I2S_RIGHT_JUSTIFIED_MODE || mode == I2S_LEFT_JUSTIFIED_MODE){
|
||||
// write the same only once - it will be automatically copied to the other channel
|
||||
I2S.write(sample);
|
||||
}
|
||||
|
||||
// increment the counter for the next sample
|
||||
count++;
|
||||
}
|
61
libraries/I2S/keywords.txt
Normal file
61
libraries/I2S/keywords.txt
Normal file
@ -0,0 +1,61 @@
|
||||
#######################################
|
||||
# Syntax Coloring Map I2S
|
||||
#######################################
|
||||
|
||||
#######################################
|
||||
# Datatypes (KEYWORD1)
|
||||
#######################################
|
||||
|
||||
I2S KEYWORD1
|
||||
|
||||
#######################################
|
||||
# Methods and Functions (KEYWORD2)
|
||||
#######################################
|
||||
I2SClass KEYWORD2
|
||||
begin KEYWORD2
|
||||
end KEYWORD2
|
||||
|
||||
onReceive KEYWORD2
|
||||
onTransmit KEYWORD2
|
||||
|
||||
setSckPin KEYWORD2
|
||||
setFsPin KEYWORD2
|
||||
setDataInPin KEYWORD2
|
||||
setDataOutPin KEYWORD2
|
||||
setAllPins KEYWORD2
|
||||
|
||||
getSckPin KEYWORD2
|
||||
getFsPin KEYWORD2
|
||||
getDataPin KEYWORD2
|
||||
getDataInPin KEYWORD2
|
||||
getDataOutPin KEYWORD2
|
||||
|
||||
setDuplex KEYWORD2
|
||||
setSimplex KEYWORD2
|
||||
isDuplex KEYWORD2
|
||||
|
||||
setBufferSize KEYWORD2
|
||||
getBufferSize KEYWORD2
|
||||
|
||||
write KEYWORD2
|
||||
availableForWrite KEYWORD2
|
||||
|
||||
read KEYWORD2
|
||||
available KEYWORD2
|
||||
|
||||
gpioToAdcUnit KEYWORD2
|
||||
gpioToAdcChannel KEYWORD2
|
||||
|
||||
#######################################
|
||||
# Constants (LITERAL1)
|
||||
#######################################
|
||||
I2S_PHILIPS_MODE LITERAL1
|
||||
I2S_RIGHT_JUSTIFIED_MODE LITERAL1
|
||||
I2S_LEFT_JUSTIFIED_MODE LITERAL1
|
||||
I2S_ADC_DAC LITERAL1
|
||||
I2S_PDM LITERAL1
|
||||
|
||||
PIN_I2S_SCK LITERAL1
|
||||
PIN_I2S_FS LITERAL1
|
||||
PIN_I2S_SD LITERAL1
|
||||
PIN_I2S_SD_OUT LITERAL1
|
9
libraries/I2S/library.properties
Normal file
9
libraries/I2S/library.properties
Normal file
@ -0,0 +1,9 @@
|
||||
name=I2S
|
||||
version=1.0
|
||||
author=Tomas Pilny
|
||||
maintainer=Tomas Pilny <tomas.pilny@espressif.com>
|
||||
sentence=Enables the communication with devices that use the Inter-IC Sound (I2S) Bus. Specific implementation for ESP.
|
||||
paragraph=
|
||||
category=Communication
|
||||
url=http://www.arduino.cc/en/Reference/I2S
|
||||
architectures=esp32
|
1208
libraries/I2S/src/I2S.cpp
Normal file
1208
libraries/I2S/src/I2S.cpp
Normal file
File diff suppressed because it is too large
Load Diff
195
libraries/I2S/src/I2S.h
Normal file
195
libraries/I2S/src/I2S.h
Normal file
@ -0,0 +1,195 @@
|
||||
/*
|
||||
Copyright (c) 2016 Arduino LLC. All right reserved.
|
||||
|
||||
This library is free software; you can redistribute it and/or
|
||||
modify it under the terms of the GNU Lesser General Public
|
||||
License as published by the Free Software Foundation; either
|
||||
version 2.1 of the License, or (at your option) any later version.
|
||||
|
||||
This library is distributed in the hope that it will be useful,
|
||||
but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
|
||||
See the GNU Lesser General Public License for more details.
|
||||
|
||||
You should have received a copy of the GNU Lesser General Public
|
||||
License along with this library; if not, write to the Free Software
|
||||
Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
|
||||
*/
|
||||
|
||||
#ifndef _I2S_H_INCLUDED
|
||||
#define _I2S_H_INCLUDED
|
||||
|
||||
#include <Arduino.h>
|
||||
#include "freertos/ringbuf.h"
|
||||
|
||||
namespace esp_i2s {
|
||||
#include "driver/i2s.h" // ESP specific i2s driver
|
||||
}
|
||||
|
||||
// Default pins
|
||||
#ifndef PIN_I2S_SCK
|
||||
#define PIN_I2S_SCK 14
|
||||
#endif
|
||||
|
||||
#ifndef PIN_I2S_FS
|
||||
#if CONFIG_IDF_TARGET_ESP32S2
|
||||
#define PIN_I2S_FS 27
|
||||
#else
|
||||
#define PIN_I2S_FS 25
|
||||
#endif
|
||||
#endif
|
||||
|
||||
#ifndef PIN_I2S_SD
|
||||
#define PIN_I2S_SD 26
|
||||
#endif
|
||||
|
||||
#ifndef PIN_I2S_SD_OUT
|
||||
#define PIN_I2S_SD_OUT 26
|
||||
#endif
|
||||
|
||||
#ifndef PIN_I2S_SD_IN
|
||||
#define PIN_I2S_SD_IN 35 // Pin 35 is only input!
|
||||
#endif
|
||||
|
||||
typedef enum {
|
||||
I2S_PHILIPS_MODE,
|
||||
I2S_RIGHT_JUSTIFIED_MODE,
|
||||
I2S_LEFT_JUSTIFIED_MODE,
|
||||
ADC_DAC_MODE,
|
||||
PDM_STEREO_MODE,
|
||||
PDM_MONO_MODE
|
||||
} i2s_mode_t;
|
||||
|
||||
class I2SClass : public Stream
|
||||
{
|
||||
public:
|
||||
// The device index and pins must map to the "COM" pads in Table 6-1 of the datasheet
|
||||
I2SClass(uint8_t deviceIndex, uint8_t clockGenerator, uint8_t sdPin, uint8_t sckPin, uint8_t fsPin);
|
||||
|
||||
// Init in MASTER mode: the SCK and FS pins are driven as outputs using the sample rate
|
||||
int begin(int mode, int sampleRate, int bitsPerSample);
|
||||
|
||||
// Init in SLAVE mode: the SCK and FS pins are inputs, other side controls sample rate
|
||||
int begin(int mode, int bitsPerSample);
|
||||
|
||||
// change pin setup and mode (default is Half Duplex)
|
||||
// Can be called only on initialized object (after begin)
|
||||
int setSckPin(int sckPin);
|
||||
int setFsPin(int fsPin);
|
||||
int setDataPin(int sdPin); // shared data pin for simplex
|
||||
int setDataOutPin(int outSdPin);
|
||||
int setDataInPin(int inSdPin);
|
||||
|
||||
int setAllPins();
|
||||
int setAllPins(int sckPin, int fsPin, int sdPin, int outSdPin, int inSdPin);
|
||||
|
||||
int getSckPin();
|
||||
int getFsPin();
|
||||
int getDataPin();
|
||||
int getDataOutPin();
|
||||
int getDataInPin();
|
||||
|
||||
int setDuplex();
|
||||
int setSimplex();
|
||||
int isDuplex();
|
||||
|
||||
void end();
|
||||
|
||||
// from Stream
|
||||
virtual int available();
|
||||
virtual int read();
|
||||
virtual int peek();
|
||||
virtual void flush();
|
||||
|
||||
// from Print
|
||||
virtual size_t write(uint8_t);
|
||||
virtual size_t write(const uint8_t *buffer, size_t size);
|
||||
|
||||
virtual int availableForWrite();
|
||||
|
||||
int read(void* buffer, size_t size);
|
||||
|
||||
//size_t write(int);
|
||||
size_t write(int32_t);
|
||||
size_t write(const void *buffer, size_t size);
|
||||
size_t write_blocking(const void *buffer, size_t size);
|
||||
size_t write_nonblocking(const void *buffer, size_t size);
|
||||
|
||||
void onTransmit(void(*)(void));
|
||||
void onReceive(void(*)(void));
|
||||
|
||||
int setBufferSize(int bufferSize);
|
||||
int getBufferSize();
|
||||
private:
|
||||
#if (SOC_I2S_SUPPORTS_ADC && SOC_I2S_SUPPORTS_DAC)
|
||||
int _gpioToAdcUnit(gpio_num_t gpio_num, esp_i2s::adc_unit_t* adc_unit);
|
||||
int _gpioToAdcChannel(gpio_num_t gpio_num, esp_i2s::adc_channel_t* adc_channel);
|
||||
#endif
|
||||
int begin(int mode, int sampleRate, int bitsPerSample, bool driveClock);
|
||||
|
||||
int _enableTransmitter();
|
||||
int _enableReceiver();
|
||||
void _onTransferComplete();
|
||||
|
||||
int _createCallbackTask();
|
||||
|
||||
static void onDmaTransferComplete(void*);
|
||||
int _installDriver();
|
||||
void _uninstallDriver();
|
||||
void _setSckPin(int sckPin);
|
||||
void _setFsPin(int fsPin);
|
||||
void _setDataPin(int sdPin);
|
||||
void _setDataOutPin(int outSdPin);
|
||||
void _setDataInPin(int inSdPin);
|
||||
int _applyPinSetting();
|
||||
|
||||
private:
|
||||
typedef enum {
|
||||
I2S_STATE_IDLE,
|
||||
I2S_STATE_TRANSMITTER,
|
||||
I2S_STATE_RECEIVER,
|
||||
I2S_STATE_DUPLEX
|
||||
} i2s_state_t;
|
||||
|
||||
int _deviceIndex;
|
||||
int _sdPin;
|
||||
int _inSdPin;
|
||||
int _outSdPin;
|
||||
int _sckPin;
|
||||
int _fsPin;
|
||||
|
||||
i2s_state_t _state;
|
||||
int _bitsPerSample;
|
||||
uint32_t _sampleRate;
|
||||
int _mode;
|
||||
|
||||
uint16_t _buffer_byte_size;
|
||||
|
||||
bool _driverInstalled; // Is IDF I2S driver installed?
|
||||
bool _initialized; // Is everything initialized (callback task, I2S driver, ring buffers)?
|
||||
TaskHandle_t _callbackTaskHandle;
|
||||
QueueHandle_t _i2sEventQueue;
|
||||
SemaphoreHandle_t _i2s_general_mutex;
|
||||
RingbufHandle_t _input_ring_buffer;
|
||||
RingbufHandle_t _output_ring_buffer;
|
||||
int _i2s_dma_buffer_size;
|
||||
bool _driveClock;
|
||||
uint32_t _peek_buff;
|
||||
bool _peek_buff_valid;
|
||||
|
||||
void _tx_done_routine(uint8_t* prev_item);
|
||||
void _rx_done_routine();
|
||||
|
||||
uint16_t _nesting_counter;
|
||||
void _take_if_not_holding();
|
||||
void _give_if_top_call();
|
||||
void _post_read_data_fix(void *input, size_t *size);
|
||||
void _fix_and_write(void *output, size_t size, size_t *bytes_written = NULL, size_t *actual_bytes_written = NULL);
|
||||
|
||||
void (*_onTransmit)(void);
|
||||
void (*_onReceive)(void);
|
||||
};
|
||||
|
||||
extern I2SClass I2S;
|
||||
|
||||
#endif
|
Reference in New Issue
Block a user