diff --git a/.cproject b/.cproject
index bedc05f8..b12dcf52 100644
--- a/.cproject
+++ b/.cproject
@@ -1,100 +1,198 @@
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
- make
-
- all
- true
- true
- true
-
-
- make
-
- size-components
- true
- true
- true
-
-
- make
-
- flash
- true
- true
- true
-
-
-
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ make
+
+
+
+ all
+
+ true
+
+ true
+
+ true
+
+
+
+
+
+ make
+
+
+
+ size-components
+
+ true
+
+ true
+
+ true
+
+
+
+
+
+ make
+
+
+
+ flash
+
+ true
+
+ true
+
+ true
+
+
+
+
+
+
+
diff --git a/.settings/language.settings.xml b/.settings/language.settings.xml
index a70f0757..bbdb7cd9 100644
--- a/.settings/language.settings.xml
+++ b/.settings/language.settings.xml
@@ -1,15 +1,28 @@
-
-
-
-
-
-
-
-
-
-
-
-
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
diff --git a/components/driver_bt/CMakeLists.txt b/components/driver_bt/CMakeLists.txt
index cb35ab91..df452446 100644
--- a/components/driver_bt/CMakeLists.txt
+++ b/components/driver_bt/CMakeLists.txt
@@ -1,6 +1,6 @@
set(COMPONENT_ADD_INCLUDEDIRS . )
-set(COMPONENT_SRCS "bt_app_core.c" )
+set(COMPONENT_SRCS "bt_app_core.c" "bt_app_sink.c" "bt_app_source.c")
set(REQUIRES esp_common)
set(REQUIRES_COMPONENTS freertos nvs_flash esp32 spi_flash newlib log console )
diff --git a/components/driver_bt/bt_app_sink.c b/components/driver_bt/bt_app_sink.c
index ef323f5a..e9bb86ae 100644
--- a/components/driver_bt/bt_app_sink.c
+++ b/components/driver_bt/bt_app_sink.c
@@ -21,6 +21,7 @@
#include "esp_gap_bt_api.h"
#include "esp_a2dp_api.h"
#include "esp_avrc_api.h"
+#include "nvs.h"
#include "freertos/FreeRTOS.h"
#include "freertos/task.h"
@@ -39,9 +40,11 @@
#define BT_RC_CT_TAG "RCCT"
#ifndef CONFIG_BT_SINK_NAME
-#define CONFIG_BT_SINK_NAME "unavailable"
+#define CONFIG_BT_SINK_NAME "default"
#endif
+extern char current_namespace[];
+
/* event for handler "bt_av_hdl_stack_up */
enum {
BT_APP_EVT_STACK_UP = 0,
@@ -352,7 +355,7 @@ static void bt_av_hdl_avrc_tg_evt(uint16_t event, void *p_param)
}
}
-void bt_sink_init(void (*cmd_cb)(bt_sink_cmd_t cmd, ...), void (*data_cb)(const uint8_t *data, uint32_t len))
+void bt_sink_init(bt_cmd_cb_t cmd_cb, bt_data_cb_t data_cb)
{
esp_err_t err;
@@ -409,6 +412,21 @@ void bt_sink_init(void (*cmd_cb)(bt_sink_cmd_t cmd, ...), void (*data_cb)(const
}
+void bt_sink_deinit(void)
+{
+ /* this still does not work, can't figure out how to stop properly this BT stack */
+ bt_app_task_shut_down();
+ ESP_LOGI(BT_AV_TAG, "bt_app_task shutdown successfully");
+ if (esp_bluedroid_disable() != ESP_OK) return;
+ ESP_LOGI(BT_AV_TAG, "esp_bluedroid_disable called successfully");
+ if (esp_bluedroid_deinit() != ESP_OK) return;
+ ESP_LOGI(BT_AV_TAG, "esp_bluedroid_deinit called successfully");
+ if (esp_bt_controller_disable() != ESP_OK) return;
+ ESP_LOGI(BT_AV_TAG, "esp_bt_controller_disable called successfully");
+ if (esp_bt_controller_deinit() != ESP_OK) return;
+ ESP_LOGI(BT_AV_TAG, "bt stopped successfully");
+}
+
static void bt_app_gap_cb(esp_bt_gap_cb_event_t event, esp_bt_gap_cb_param_t *param)
{
switch (event) {
@@ -449,9 +467,17 @@ static void bt_av_hdl_stack_evt(uint16_t event, void *p_param)
switch (event) {
case BT_APP_EVT_STACK_UP: {
/* set up device name */
- char *dev_name = CONFIG_BT_SINK_NAME;
- esp_bt_dev_set_device_name(dev_name);
-
+ nvs_handle nvs;
+ char dev_name[32] = CONFIG_BT_SINK_NAME;
+
+ if (nvs_open(current_namespace, NVS_READONLY, &nvs) == ESP_OK) {
+ size_t len = 31;
+ nvs_get_str(nvs, "bt_sink_name", dev_name, &len);
+ nvs_close(nvs);
+ }
+
+ esp_bt_dev_set_device_name(dev_name);
+
esp_bt_gap_register_callback(bt_app_gap_cb);
/* initialize AVRCP controller */
diff --git a/components/driver_bt/bt_app_sink.h b/components/driver_bt/bt_app_sink.h
index 9c84446e..aa641bc8 100644
--- a/components/driver_bt/bt_app_sink.h
+++ b/components/driver_bt/bt_app_sink.h
@@ -13,10 +13,23 @@
typedef enum { BT_SINK_CONNECTED, BT_SINK_DISCONNECTED, BT_SINK_PLAY, BT_SINK_STOP, BT_SINK_PAUSE,
BT_SINK_RATE, BT_SINK_VOLUME, } bt_sink_cmd_t;
+
+typedef void (*bt_cmd_cb_t)(bt_sink_cmd_t cmd, ...);
+typedef void (*bt_data_cb_t)(const uint8_t *data, uint32_t len);
/**
* @brief init sink mode (need to be provided)
*/
-void bt_sink_init(void (*cmd_cb)(bt_sink_cmd_t cmd, ...), void (*data_cb)(const uint8_t *data, uint32_t len));
+void bt_sink_init(bt_cmd_cb_t cmd_cb, bt_data_cb_t data_cb);
+
+/**
+ * @brief deinit sink mode (need to be provided)
+ */
+void bt_sink_deinit(void);
+
+/**
+ * @brief local command mode (stop, play, volume ...)
+ */
+void bt_sink_cmd(bt_sink_cmd_t event, ...);
#endif /* __BT_APP_SINK_H__*/
diff --git a/components/driver_bt/component.mk b/components/driver_bt/component.mk
index 0c83faa9..e694d472 100644
--- a/components/driver_bt/component.mk
+++ b/components/driver_bt/component.mk
@@ -7,5 +7,6 @@
# please read the SDK documents if you need to do this.
#
-CFLAGS += -I$(COMPONENT_PATH)/../tools
+CFLAGS += -I$(COMPONENT_PATH)/../tools
+
#CFLAGS += -DLOG_LOCAL_LEVEL=ESP_LOG_DEBUG
diff --git a/components/io/led.c b/components/io/led.c
index 702db2cb..10f2b901 100644
--- a/components/io/led.c
+++ b/components/io/led.c
@@ -109,6 +109,7 @@ bool led_unconfig(int idx) {
if (idx >= MAX_LED) return false;
if (leds[idx].timer) xTimerDelete(leds[idx].timer, BLOCKTIME);
+ leds[idx].timer = NULL;
return true;
}
diff --git a/components/squeezelite/buffer.c b/components/squeezelite/buffer.c
index ed71d811..076fd990 100644
--- a/components/squeezelite/buffer.c
+++ b/components/squeezelite/buffer.c
@@ -64,6 +64,11 @@ void buf_flush(struct buffer *buf) {
mutex_unlock(buf->mutex);
}
+void _buf_flush(struct buffer *buf) {
+ buf->readp = buf->buf;
+ buf->writep = buf->buf;
+}
+
// adjust buffer to multiple of mod bytes so reading in multiple always wraps on frame boundary
void buf_adjust(struct buffer *buf, size_t mod) {
size_t size;
@@ -78,6 +83,7 @@ void buf_adjust(struct buffer *buf, size_t mod) {
// called with mutex locked to resize, does not retain contents, reverts to original size if fails
void _buf_resize(struct buffer *buf, size_t size) {
+ if (size == buf->size) return;
free(buf->buf);
buf->buf = malloc(size);
if (!buf->buf) {
diff --git a/components/squeezelite/component.mk b/components/squeezelite/component.mk
index 1d9abe13..0d60996d 100644
--- a/components/squeezelite/component.mk
+++ b/components/squeezelite/component.mk
@@ -13,7 +13,8 @@ CFLAGS += -O3 -DLINKALL -DLOOPBACK -DNO_FAAD -DRESAMPLE16 -DEMBEDDED -DTREMOR_ON
-I$(COMPONENT_PATH)/../tools \
-I$(COMPONENT_PATH)/../codecs/inc/opus \
-I$(COMPONENT_PATH)/../codecs/inc/opusfile \
- -I$(COMPONENT_PATH)/../driver_bt
+ -I$(COMPONENT_PATH)/../driver_bt \
+ -I$(COMPONENT_PATH)/../raop
# -I$(COMPONENT_PATH)/../codecs/inc/faad2
diff --git a/components/squeezelite/decode.c b/components/squeezelite/decode.c
index 333af5df..cc59f77a 100644
--- a/components/squeezelite/decode.c
+++ b/components/squeezelite/decode.c
@@ -116,6 +116,10 @@ static void *decode_thread() {
usleep(100000);
}
}
+
+#if EMBEDDED
+ deregister_external();
+#endif
return 0;
}
@@ -200,7 +204,7 @@ void decode_init(log_level level, const char *include_codecs, const char *exclud
sort_codecs((include_codecs ? order_codecs - include_codecs : i), register_mpg());
#if EMBEDDED
- register_other();
+ register_external();
#endif
LOG_DEBUG("include codecs: %s exclude codecs: %s", include_codecs ? include_codecs : "", exclude_codecs);
diff --git a/components/squeezelite/decode_bt.c b/components/squeezelite/decode_bt.c
deleted file mode 100644
index 572b8860..00000000
--- a/components/squeezelite/decode_bt.c
+++ /dev/null
@@ -1,141 +0,0 @@
-/*
- * Squeezelite for esp32
- *
- * (c) Sebastien 2019
- * Philippe G. 2019, philippe_44@outlook.com
- *
- * This program is free software: you can redistribute it and/or modify
- * it under the terms of the GNU General Public License as published by
- * the Free Software Foundation, either version 3 of the License, or
- * (at your option) any later version.
- *
- * This program 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 General Public License for more details.
- *
- * You should have received a copy of the GNU General Public License
- * along with this program. If not, see .
- *
- */
-
-#include "squeezelite.h"
-#include "bt_app_sink.h"
-
-#define LOCK_O mutex_lock(outputbuf->mutex)
-#define UNLOCK_O mutex_unlock(outputbuf->mutex)
-#define LOCK_D mutex_lock(decode.mutex);
-#define UNLOCK_D mutex_unlock(decode.mutex);
-
-extern struct outputstate output;
-extern struct decodestate decode;
-extern struct buffer *outputbuf;
-// this is the only system-wide loglevel variable
-extern log_level loglevel;
-
-/****************************************************************************************
- * BT sink data handler
- */
-static void bt_sink_data_handler(const uint8_t *data, uint32_t len)
-{
- size_t bytes;
-
- // would be better to lock decoder, but really, it does not matter
- if (decode.state != DECODE_STOPPED) {
- LOG_WARN("Cannot use BT sink while LMS is controlling player");
- return;
- }
-
- // there will always be room at some point
- while (len) {
- LOCK_O;
-
- bytes = min(len, _buf_cont_write(outputbuf));
-#if BYTES_PER_FRAME == 4
- memcpy(outputbuf->writep, data, bytes);
-#else
- {
- s16_t *iptr = (s16_t*) data;
- ISAMPLE_T *optr = (ISAMPLE_T*) outputbuf->writep;
- size_t n = bytes / BYTES_PER_FRAME * 2;
- while (n--) *optr++ = *iptr++ << 16;
- }
-#endif
- _buf_inc_writep(outputbuf, bytes);
- len -= bytes;
- data += bytes;
-
- UNLOCK_O;
-
- // allow i2s to empty the buffer if needed
- if (len) usleep(50000);
- }
-}
-
-/****************************************************************************************
- * BT sink command handler
- */
-static void bt_sink_cmd_handler(bt_sink_cmd_t cmd, ...)
-{
- va_list args;
-
- LOCK_D;
- if (decode.state != DECODE_STOPPED) {
- LOG_WARN("Cannot use BT sink while LMS is controlling player");
- UNLOCK_D;
- return;
- }
-
- va_start(args, cmd);
-
- if (cmd != BT_SINK_VOLUME) LOCK_O;
-
- switch(cmd) {
- case BT_SINK_CONNECTED:
- output.state = OUTPUT_STOPPED;
- LOG_INFO("BT sink started");
- break;
- case BT_SINK_DISCONNECTED:
- output.state = OUTPUT_OFF;
- LOG_INFO("BT sink stopped");
- break;
- case BT_SINK_PLAY:
- output.state = OUTPUT_EXTERNAL;
- LOG_INFO("BT sink playing");
- break;
- case BT_SINK_PAUSE:
- case BT_SINK_STOP:
- output.state = OUTPUT_STOPPED;
- LOG_INFO("BT sink stopped");
- break;
- case BT_SINK_RATE:
- output.current_sample_rate = va_arg(args, u32_t);
- LOG_INFO("Setting BT sample rate %u", output.current_sample_rate);
- break;
- case BT_SINK_VOLUME: {
- u16_t volume = (u16_t) va_arg(args, u32_t);
- volume *= 65536 / 128;
- set_volume(volume, volume);
- break;
- }
- }
-
- if (cmd != BT_SINK_VOLUME) UNLOCK_O;
- UNLOCK_D;
-
- va_end(args);
-}
-
-/****************************************************************************************
- * We provide the generic codec register option
- */
-void register_other(void) {
-#ifdef CONFIG_BT_SINK
- if (!strcasestr(output.device, "BT ")) {
- bt_sink_init(bt_sink_cmd_handler, bt_sink_data_handler);
- LOG_INFO("Initializing BT sink");
- } else {
- LOG_WARN("Cannot be a BT sink and source");
- }
-#endif
-}
diff --git a/components/squeezelite/embedded.h b/components/squeezelite/embedded.h
index f96c6c24..8db425ab 100644
--- a/components/squeezelite/embedded.h
+++ b/components/squeezelite/embedded.h
@@ -19,10 +19,10 @@
#define PTHREAD_STACK_MIN 256
#endif
-#define STREAM_THREAD_STACK_SIZE 8 * 1024
-#define DECODE_THREAD_STACK_SIZE 20 * 1024
-#define OUTPUT_THREAD_STACK_SIZE 8 * 1024
-#define IR_THREAD_STACK_SIZE 8 * 1024
+#define STREAM_THREAD_STACK_SIZE 6 * 1024
+#define DECODE_THREAD_STACK_SIZE 16 * 1024
+#define OUTPUT_THREAD_STACK_SIZE 6 * 1024
+#define IR_THREAD_STACK_SIZE 6 * 1024
//#define BASE_CAP "Model=squeezelite,AccuratePlayPoints=0,HasDigitalOut=1,HasPolarityInversion=1,Firmware=" VERSION
@@ -36,9 +36,13 @@ typedef unsigned long long u64_t;
#define gettime_ms _gettime_ms_
#define mutex_create_p(m) mutex_create(m)
-uint32_t _gettime_ms_(void);
-int pthread_create_name(pthread_t *thread, _CONST pthread_attr_t *attr,
+uint32_t _gettime_ms_(void);
+
+int pthread_create_name(pthread_t *thread, _CONST pthread_attr_t *attr,
void *(*start_routine)( void * ), void *arg, char *name);
-void register_other(void);
+
+// these are here as they can be #define to nothing
+void register_external(void);
+void deregister_external(void);
#endif // EMBEDDED_H
diff --git a/components/squeezelite/opus.c b/components/squeezelite/opus.c
index 73cd86a0..f20ebe42 100644
--- a/components/squeezelite/opus.c
+++ b/components/squeezelite/opus.c
@@ -139,7 +139,7 @@ static decode_state opus_decompress(void) {
info = OP(u, head, u->of, -1);
LOCK_O;
- output.next_sample_rate = 48000;
+ output.next_sample_rate = decode_newstream(48000, output.supported_rates);
IF_DSD( output.next_fmt = PCM; )
output.track_start = outputbuf->writep;
if (output.fade_mode) _checkfade(true);
diff --git a/components/squeezelite/output.c b/components/squeezelite/output.c
index e79c5c6d..f41a032b 100644
--- a/components/squeezelite/output.c
+++ b/components/squeezelite/output.c
@@ -345,8 +345,9 @@ void output_init_common(log_level level, const char *device, unsigned output_buf
unsigned i;
loglevel = level;
-
+
output_buf_size = output_buf_size - (output_buf_size % BYTES_PER_FRAME);
+ output.init_size = output_buf_size;
LOG_DEBUG("outputbuf size: %u", output_buf_size);
buf_init(outputbuf, output_buf_size);
diff --git a/components/squeezelite/output_bt.c b/components/squeezelite/output_bt.c
index d7080e21..15101d76 100644
--- a/components/squeezelite/output_bt.c
+++ b/components/squeezelite/output_bt.c
@@ -19,6 +19,7 @@
*
*/
+#include "driver/gpio.h"
#include "squeezelite.h"
#include "perf_trace.h"
@@ -38,10 +39,12 @@ extern u8_t *silencebuf;
extern void hal_bluetooth_init(const char * options);
extern void hal_bluetooth_stop(void);
+extern u8_t config_spdif_gpio;
static log_level loglevel;
static bool running = false;
-uint8_t * btout;
+static uint8_t *btout;
+static frames_t oframes;
static int _write_frames(frames_t out_frames, bool silence, s32_t gainL, s32_t gainR,
s32_t cross_gain_in, s32_t cross_gain_out, ISAMPLE_T **cross_ptr);
@@ -65,6 +68,11 @@ static int _write_frames(frames_t out_frames, bool silence, s32_t gainL, s32_t g
DECLARE_ALL_MIN_MAX;
void output_init_bt(log_level level, char *device, unsigned output_buf_size, char *params, unsigned rates[], unsigned rate_delay, unsigned idle) {
+#ifdef CONFIG_SQUEEZEAMP
+ gpio_pad_select_gpio(config_spdif_gpio);
+ gpio_set_direction(config_spdif_gpio, GPIO_MODE_OUTPUT);
+ gpio_set_level(config_spdif_gpio, 0);
+#endif
loglevel = level;
running = true;
output.write_cb = &_write_frames;
@@ -94,12 +102,12 @@ static int _write_frames(frames_t out_frames, bool silence, s32_t gainL, s32_t g
}
#if BYTES_PER_FRAME == 4
- memcpy(btout, outputbuf->readp, out_frames * BYTES_PER_FRAME);
+ memcpy(btout + oframes * BYTES_PER_FRAME, outputbuf->readp, out_frames * BYTES_PER_FRAME);
#else
{
frames_t count = out_frames;
s32_t *_iptr = (s32_t*) outputbuf->readp;
- s16_t *_optr = (s16_t*) bt_optr;
+ s16_t *_optr = (s16_t*) (btout + oframes * BYTES_PER_FRAME);
while (count--) {
*_optr++ = *_iptr++ >> 16;
*_optr++ = *_iptr++ >> 16;
@@ -110,7 +118,7 @@ static int _write_frames(frames_t out_frames, bool silence, s32_t gainL, s32_t g
} else {
u8_t *buf = silencebuf;
- memcpy(btout, buf, out_frames * BYTES_PER_FRAME);
+ memcpy(btout + oframes * BYTES_PER_FRAME, buf, out_frames * BYTES_PER_FRAME);
}
return (int)out_frames;
@@ -124,6 +132,7 @@ int32_t output_bt_data(uint8_t *data, int32_t len) {
}
btout = data;
+ oframes = 0;
// This is how the BTC layer calculates the number of bytes to
// for us to send. (BTC_SBC_DEC_PCM_DATA_LEN * sizeof(OI_INT16) - availPcmBytes
@@ -143,6 +152,7 @@ int32_t output_bt_data(uint8_t *data, int32_t len) {
if (wanted_len > 0) {
SET_MIN_MAX(wanted_len, under);
}
+ output.frames_in_process = len-wanted_len;
UNLOCK;
SET_MIN_MAX(TIME_MEASUREMENT_GET(start_timer),lock_out_time);
diff --git a/components/squeezelite/output_i2s.c b/components/squeezelite/output_i2s.c
index f8f2132b..e4b8ed20 100644
--- a/components/squeezelite/output_i2s.c
+++ b/components/squeezelite/output_i2s.c
@@ -41,6 +41,7 @@ sure that using rate_delay would fix that
*/
#include "squeezelite.h"
+#include "esp_pthread.h"
#include "driver/i2s.h"
#include "driver/i2c.h"
#include "driver/gpio.h"
@@ -84,9 +85,9 @@ sure that using rate_delay would fix that
typedef enum { DAC_ON = 0, DAC_OFF, DAC_POWERDOWN, DAC_VOLUME } dac_cmd_e;
-// must have an integer ratio with FRAME_BLOCK
+// must have an integer ratio with FRAME_BLOCK (see spdif comment)
#define DMA_BUF_LEN 512
-#define DMA_BUF_COUNT 16
+#define DMA_BUF_COUNT 12
#define DECLARE_ALL_MIN_MAX \
DECLARE_MIN_MAX(o); \
@@ -115,7 +116,9 @@ static i2s_config_t i2s_config;
static int bytes_per_frame;
static thread_type thread, stats_thread;
static u8_t *obuf;
+static frames_t oframes;
static bool spdif;
+static size_t dma_buf_frames;
DECLARE_ALL_MIN_MAX;
@@ -151,12 +154,14 @@ static void spdif_convert(ISAMPLE_T *src, size_t frames, u32_t *dst, size_t *cou
#define I2C_PORT 0
#define I2C_ADDR 0x4c
#define VOLUME_GPIO 33
-#define JACK_GPIO 39
+#define JACK_GPIO 34
struct tas575x_cmd_s {
u8_t reg;
u8_t value;
};
+
+u8_t config_spdif_gpio = CONFIG_SPDIF_DO_IO;
static const struct tas575x_cmd_s tas575x_init_sequence[] = {
{ 0x00, 0x00 }, // select page 0
@@ -192,9 +197,9 @@ void output_init_i2s(log_level level, char *device, unsigned output_buf_size, ch
#ifdef TAS575x
gpio_pad_select_gpio(JACK_GPIO);
gpio_set_direction(JACK_GPIO, GPIO_MODE_INPUT);
-
+
adc1_config_width(ADC_WIDTH_BIT_12);
- adc1_config_channel_atten(ADC1_CHANNEL_0,ADC_ATTEN_DB_0);
+ adc1_config_channel_atten(ADC1_CHANNEL_7, ADC_ATTEN_DB_0);
// init volume & mute
gpio_pad_select_gpio(VOLUME_GPIO);
@@ -266,27 +271,37 @@ void output_init_i2s(log_level level, char *device, unsigned output_buf_size, ch
};
i2s_config.sample_rate = output.current_sample_rate * 2;
i2s_config.bits_per_sample = 32;
+ // Normally counted in frames, but 16 sample are transformed into 32 bits in spdif
+ i2s_config.dma_buf_len = DMA_BUF_LEN / 2;
+ i2s_config.dma_buf_count = DMA_BUF_COUNT * 2;
+ /*
+ In DMA, we have room for (LEN * COUNT) frames of 32 bits samples that
+ we push at sample_rate * 2. Each of these peuso-frames is a single true
+ audio frame. So the real depth is true frames is (LEN * COUNT / 2)
+ */
+ dma_buf_frames = DMA_BUF_COUNT * DMA_BUF_LEN / 2;
} else {
pin_config = (i2s_pin_config_t) { .bck_io_num = CONFIG_I2S_BCK_IO, .ws_io_num = CONFIG_I2S_WS_IO,
.data_out_num = CONFIG_I2S_DO_IO, .data_in_num = -1 //Not used
};
i2s_config.sample_rate = output.current_sample_rate;
i2s_config.bits_per_sample = bytes_per_frame * 8 / 2;
-#ifdef TAS575x
+ // Counted in frames (but i2s allocates a buffer <= 4092 bytes)
+ i2s_config.dma_buf_len = DMA_BUF_LEN;
+ i2s_config.dma_buf_count = DMA_BUF_COUNT;
+ dma_buf_frames = DMA_BUF_COUNT * DMA_BUF_LEN;
+#ifdef TAS575x
gpio_pad_select_gpio(CONFIG_SPDIF_DO_IO);
gpio_set_direction(CONFIG_SPDIF_DO_IO, GPIO_MODE_OUTPUT);
gpio_set_level(CONFIG_SPDIF_DO_IO, 0);
#endif
}
-
+
i2s_config.mode = I2S_MODE_MASTER | I2S_MODE_TX;
i2s_config.channel_format = I2S_CHANNEL_FMT_RIGHT_LEFT;
i2s_config.communication_format = I2S_COMM_FORMAT_I2S| I2S_COMM_FORMAT_I2S_MSB;
// in case of overflow, do not replay old buffer
i2s_config.tx_desc_auto_clear = true;
- i2s_config.dma_buf_count = DMA_BUF_COUNT;
- // Counted in frames (but i2s allocates a buffer <= 4092 bytes)
- i2s_config.dma_buf_len = DMA_BUF_LEN;
i2s_config.use_apll = true;
i2s_config.intr_alloc_flags = ESP_INTR_FLAG_LEVEL1; //Interrupt level 1
@@ -301,15 +316,21 @@ void output_init_i2s(log_level level, char *device, unsigned output_buf_size, ch
isI2SStarted=false;
dac_cmd(DAC_OFF);
-
- pthread_attr_t attr;
- pthread_attr_init(&attr);
- pthread_attr_setstacksize(&attr, PTHREAD_STACK_MIN + OUTPUT_THREAD_STACK_SIZE);
- pthread_create_name(&thread, &attr, output_thread_i2s, NULL, "output_i2s");
- pthread_attr_destroy(&attr);
- // leave stack size to default
- pthread_create_name(&stats_thread, NULL, output_thread_i2s_stats, NULL, "output_i2s_sts");
+ esp_pthread_cfg_t cfg = esp_pthread_get_default_config();
+
+ cfg.thread_name= "output_i2s";
+ cfg.inherit_cfg = false;
+ cfg.prio = CONFIG_ESP32_PTHREAD_TASK_PRIO_DEFAULT + 1;
+ cfg.stack_size = PTHREAD_STACK_MIN + OUTPUT_THREAD_STACK_SIZE;
+ esp_pthread_set_cfg(&cfg);
+ pthread_create(&thread, NULL, output_thread_i2s, NULL);
+
+ cfg.thread_name= "output_i2s_sts";
+ cfg.prio = CONFIG_ESP32_PTHREAD_TASK_PRIO_DEFAULT - 1;
+ cfg.stack_size = 2048;
+ esp_pthread_set_cfg(&cfg);
+ pthread_create(&stats_thread, NULL, output_thread_i2s_stats, NULL);
}
@@ -361,13 +382,13 @@ static int _i2s_write_frames(frames_t out_frames, bool silence, s32_t gainL, s32
_apply_gain(outputbuf, out_frames, gainL, gainR);
}
- memcpy(obuf, outputbuf->readp, out_frames * bytes_per_frame);
+ memcpy(obuf + oframes * bytes_per_frame, outputbuf->readp, out_frames * bytes_per_frame);
#else
optr = (s32_t*) outputbuf->readp;
#endif
} else {
#if BYTES_PER_FRAME == 4
- memcpy(obuf, silencebuf, out_frames * bytes_per_frame);
+ memcpy(obuf + oframes * bytes_per_frame, silencebuf, out_frames * bytes_per_frame);
#else
optr = (s32_t*) silencebuf;
#endif
@@ -381,19 +402,20 @@ static int _i2s_write_frames(frames_t out_frames, bool silence, s32_t gainL, s32
dsd_invert((u32_t *) optr, out_frames);
)
- _scale_and_pack_frames(obuf, optr, out_frames, gainL, gainR, output.format);
+ _scale_and_pack_frames(obuf + oframes * bytes_per_frame, optr, out_frames, gainL, gainR, output.format);
#endif
+ oframes += out_frames;
+
return out_frames;
}
-
/****************************************************************************************
* Main output thread
*/
static void *output_thread_i2s() {
size_t count = 0, bytes;
- frames_t iframes = FRAME_BLOCK, oframes;
+ frames_t iframes = FRAME_BLOCK;
uint32_t timer_start = 0;
int discard = 0;
uint32_t fullness = gettime_ms();
@@ -404,14 +426,14 @@ static void *output_thread_i2s() {
// spdif needs 16 bytes per frame : 32 bits/sample, 2 channels, BMC encoded
if (spdif && (sbuf = malloc(FRAME_BLOCK * 16)) == NULL) {
LOG_ERROR("Cannot allocate SPDIF buffer");
- }
+ }
while (running) {
TIME_MEASUREMENT_START(timer_start);
LOCK;
-
+
// manage led display
if (state != output.state) {
LOG_INFO("Output state is %d", output.state);
@@ -435,12 +457,15 @@ static void *output_thread_i2s() {
synced = false;
}
+ oframes = 0;
output.updated = gettime_ms();
output.frames_played_dmp = output.frames_played;
- // try to estimate how much we have consumed from the DMA buffer
- output.device_frames = DMA_BUF_COUNT * DMA_BUF_LEN - ((output.updated - fullness) * output.current_sample_rate) / 1000;
- oframes = _output_frames( iframes );
-
+ // try to estimate how much we have consumed from the DMA buffer (calculation is incorrect at the very beginning ...)
+ output.device_frames = dma_buf_frames - ((output.updated - fullness) * output.current_sample_rate) / 1000;
+ _output_frames( iframes );
+ // oframes must be a global updated by the write callback
+ output.frames_in_process = oframes;
+
SET_MIN_MAX_SIZED(oframes,rec,iframes);
SET_MIN_MAX_SIZED(_buf_used(outputbuf),o,outputbuf->size);
SET_MIN_MAX_SIZED(_buf_used(streambuf),s,streambuf->size);
@@ -501,7 +526,7 @@ static void *output_thread_i2s() {
if (bytes != oframes * bytes_per_frame) {
LOG_WARN("I2S DMA Overflow! available bytes: %d, I2S wrote %d bytes", oframes * bytes_per_frame, bytes);
}
-
+
SET_MIN_MAX( TIME_MEASUREMENT_GET(timer_start),i2s_time);
}
@@ -517,7 +542,7 @@ static void *output_thread_i2s() {
static void *output_thread_i2s_stats() {
while (running) {
#ifdef TAS575x
- LOG_ERROR("Jack %d Voltage %.2fV", !gpio_get_level(JACK_GPIO), adc1_get_raw(ADC1_CHANNEL_0) / 4095. * (10+169)/10. * 1.1);
+ LOG_ERROR("Jack %d Voltage %.2fV", !gpio_get_level(JACK_GPIO), adc1_get_raw(ADC1_CHANNEL_7) / 4095. * (10+174)/10. * 1.1);
#endif
LOCK;
output_state state = output.state;
@@ -542,6 +567,11 @@ static void *output_thread_i2s_stats() {
LOG_INFO(" ----------+----------+-----------+-----------+");
RESET_ALL_MIN_MAX;
}
+ LOG_INFO("Heap internal:%zu (min:%zu) external:%zu (min:%zu)",
+ heap_caps_get_free_size(MALLOC_CAP_INTERNAL),
+ heap_caps_get_minimum_free_size(MALLOC_CAP_INTERNAL),
+ heap_caps_get_free_size(MALLOC_CAP_SPIRAM),
+ heap_caps_get_minimum_free_size(MALLOC_CAP_SPIRAM));
usleep(STATS_PERIOD_MS *1000);
}
return NULL;
diff --git a/components/squeezelite/slimproto.c b/components/squeezelite/slimproto.c
index e301d13e..42fb73b0 100644
--- a/components/squeezelite/slimproto.c
+++ b/components/squeezelite/slimproto.c
@@ -371,6 +371,8 @@ static void process_strm(u8_t *pkt, int len) {
sendSTAT("STMc", 0);
sentSTMu = sentSTMo = sentSTMl = false;
LOCK_O;
+ output.external = false;
+ _buf_resize(outputbuf, output.init_size);
output.threshold = strm->output_threshold;
output.next_replay_gain = unpackN(&strm->replay_gain);
output.fade_mode = strm->transition_type - '0';
@@ -629,7 +631,6 @@ static void slimproto_run() {
#endif
last = now;
-
LOCK_S;
status.stream_full = _buf_used(streambuf);
status.stream_size = streambuf->size;
@@ -688,7 +689,7 @@ static void slimproto_run() {
status.current_sample_rate = output.current_sample_rate;
status.updated = output.updated;
status.device_frames = output.device_frames;
-
+
if (output.track_started) {
_sendSTMs = true;
output.track_started = false;
@@ -703,7 +704,7 @@ static void slimproto_run() {
if (_start_output && (output.state == OUTPUT_STOPPED || output.state == OUTPUT_OFF)) {
output.state = OUTPUT_BUFFER;
}
- if (output.state == OUTPUT_RUNNING && !sentSTMu && status.output_full == 0 && status.stream_state <= DISCONNECT &&
+ if (!output.external && output.state == OUTPUT_RUNNING && !sentSTMu && status.output_full == 0 && status.stream_state <= DISCONNECT &&
_decode_state == DECODE_STOPPED) {
_sendSTMu = true;
@@ -721,7 +722,7 @@ static void slimproto_run() {
output.state = OUTPUT_OFF;
LOG_DEBUG("output timeout");
}
- if (output.state == OUTPUT_RUNNING && now - status.last > 1000) {
+ if (!output.external && output.state == OUTPUT_RUNNING && now - status.last > 1000) {
_sendSTMt = true;
status.last = now;
}
diff --git a/components/squeezelite/squeezelite.h b/components/squeezelite/squeezelite.h
index b51247a3..8de70146 100644
--- a/components/squeezelite/squeezelite.h
+++ b/components/squeezelite/squeezelite.h
@@ -539,6 +539,7 @@ unsigned _buf_cont_write(struct buffer *buf);
void _buf_inc_readp(struct buffer *buf, unsigned by);
void _buf_inc_writep(struct buffer *buf, unsigned by);
void buf_flush(struct buffer *buf);
+void _buf_flush(struct buffer *buf);
void buf_adjust(struct buffer *buf, size_t mod);
void _buf_resize(struct buffer *buf, size_t size);
void buf_init(struct buffer *buf, size_t size);
@@ -634,7 +635,7 @@ bool resample_init(char *opt);
// output.c output_alsa.c output_pa.c output_pack.c
typedef enum { OUTPUT_OFF = -1, OUTPUT_STOPPED = 0, OUTPUT_BUFFER, OUTPUT_RUNNING,
- OUTPUT_PAUSE_FRAMES, OUTPUT_SKIP_FRAMES, OUTPUT_START_AT, OUTPUT_EXTERNAL } output_state;
+ OUTPUT_PAUSE_FRAMES, OUTPUT_SKIP_FRAMES, OUTPUT_START_AT } output_state;
#if DSD
typedef enum { PCM, DOP, DSD_U8, DSD_U16_LE, DSD_U32_LE, DSD_U16_BE, DSD_U32_BE, DOP_S24_LE, DOP_S24_3LE } dsd_format;
@@ -654,6 +655,8 @@ struct outputstate {
output_state state;
output_format format;
const char *device;
+ bool external;
+ u32_t init_size;
#if ALSA
unsigned buffer;
unsigned period;
@@ -673,6 +676,7 @@ struct outputstate {
unsigned default_sample_rate;
bool error_opening;
unsigned device_frames;
+ unsigned frames_in_process;
u32_t updated;
u32_t track_start_time;
u32_t current_replay_gain;
diff --git a/main/CMakeLists.txt b/main/CMakeLists.txt
index 974bcda3..e1caadf7 100644
--- a/main/CMakeLists.txt
+++ b/main/CMakeLists.txt
@@ -1,6 +1,6 @@
set(COMPONENT_ADD_INCLUDEDIRS . )
-set(COMPONENT_SRCS "esp_app_main.c" "platform_esp32.c" "cmd_wifi.c" "console.c" "nvs_utilities.c" "cmd_squeezelite.c")
+set(COMPONENT_SRCS "esp_app_main.c" "platform_esp32.c" "cmd_wifi.c" "console.c" "nvs_utilities.c" "cmd_squeezelite.c" )
set(REQUIRES esp_common )
set(REQUIRES_COMPONENTS freertos nvs_flash esp32 spi_flash newlib log console wifi-manager )
diff --git a/main/Kconfig.projbuild b/main/Kconfig.projbuild
index b009ab04..e6c29b69 100644
--- a/main/Kconfig.projbuild
+++ b/main/Kconfig.projbuild
@@ -229,7 +229,7 @@ menu "Squeezelite-ESP32"
config BT_SINK_NAME
depends on BT_SINK
string "Name of Bluetooth A2DP device"
- default "ESP32"
+ default "ESP32-BT"
help
This is the name of the bluetooth speaker that will be broadcasted
config BT_SINK_PIN
@@ -237,8 +237,20 @@ menu "Squeezelite-ESP32"
int "Bluetooth PIN code"
default 1234
config AIRPLAY_SINK
- bool "AirPlay receiver (not availabe now)"
- default n
+ bool "AirPlay receiver"
+ default y
+ config AIRPLAY_NAME
+ depends on AIRPLAY_SINK
+ string "Name of AirPlay device"
+ default "ESP32-AirPlay"
+ help
+ This is the name of the AirPlay speaker that will be broadcasted
+ config AIRPLAY_PORT
+ depends on AIRPLAY_SINK
+ string "AirPlay listening port"
+ default 5000
+ help
+ AirPlay service listening port
endmenu
endmenu
\ No newline at end of file
diff --git a/main/cmd_squeezelite.c b/main/cmd_squeezelite.c
index 3278d9db..b042ab5c 100644
--- a/main/cmd_squeezelite.c
+++ b/main/cmd_squeezelite.c
@@ -17,7 +17,7 @@
#include "nvs_flash.h"
//extern char current_namespace[];
static const char * TAG = "squeezelite_cmd";
-#define SQUEEZELITE_THREAD_STACK_SIZE 8192
+#define SQUEEZELITE_THREAD_STACK_SIZE (6*1024)
extern int main(int argc, char **argv);
static int launchsqueezelite(int argc, char **argv);
pthread_t thread_squeezelite;
diff --git a/main/console.c b/main/console.c
index 26d1ed1f..61ec537b 100644
--- a/main/console.c
+++ b/main/console.c
@@ -29,7 +29,6 @@
#include "cmd_squeezelite.h"
#include "nvs_utilities.h"
pthread_t thread_console;
-
static void * console_thread();
void console_start();
static const char * TAG = "console";
@@ -146,12 +145,9 @@ void process_autoexec(){
{
ESP_LOGD(TAG,"No matching command found for name autoexec. Adding default entries");
uint8_t autoexec_dft=0;
- //char autoexec1_dft[64];
- char autoexec1_dft[]="squeezelite -o \"I2S\" -b 500:2000 -d all=info -M esp32";
- //snprintf(autoexec1_dft, 64, "join %s %s", CONFIG_WIFI_SSID, CONFIG_WIFI_PASSWORD);
+ char autoexec1_dft[256]="squeezelite -o \"I2S\" -b 500:2000 -d all=info -M esp32";
store_nvs_value(NVS_TYPE_U8,"autoexec",&autoexec_dft);
store_nvs_value(NVS_TYPE_STR,"autoexec1",autoexec1_dft);
- //store_nvs_value(NVS_TYPE_STR,"autoexec2",autoexec2_dft);
}
}
static void initialize_filesystem() {
@@ -276,7 +272,6 @@ void console_start() {
pthread_attr_t attr;
pthread_attr_init(&attr);
pthread_create(&thread_console, &attr, console_thread, NULL);
-
pthread_attr_destroy(&attr);
}
void run_command(char * line){
diff --git a/partitions.csv b/partitions.csv
index d02a1a7e..2c630f34 100644
--- a/partitions.csv
+++ b/partitions.csv
@@ -1,7 +1,7 @@
-nvs, data, nvs, 0x9000, 0x4000,
-otadata, data, ota, 0xD000, 0x2000,
-phy_init, data, phy, 0xF000, 0x1000,
-factory, app, factory, 0x10000, 0x140000,
-ota_0, app, ota_0, 0x150000, 0x270000,
-coredump, data, coredump, 0x3C0000, 0x10000,
-storage, data, fat, 0x3D0000, 0x30000,
+# Name, Type, SubType, Offset, Size, Flags
+# Note: if you change the phy_init or app partition offset, make sure to change the offset in Kconfig.projbuild
+nvs, data, nvs, 0x9000, 0x6000,
+phy_init, data, phy, 0xf000, 0x1000,
+factory, app, factory, 0x10000, 2M,
+storage, data, fat, , 819200,
+coredump, data, coredump,, 64K
\ No newline at end of file