Muse Luxe Aux In

Greetings,

I have 2 Muse Luxe speakers. I have been using them with the Squeezelite firmware for over a year without any problems.

Now I wanted to use them to improve the sound for my Home Assitant Voice PE and use the AUX in connection.

But when I install the Bluetooth firmware from here https://raspiaudio.github.io/ on both Muse Luxe speakers, no sound comes out via the Aux in port when I connect the Home Assistant Voice.

I also noticed that when I connect to the speakers via Bluetooth and then play music, after about 5 seconds there is a loud static noise on both speakers and they restart. Is this behavior known and does anyone know what to do to fix it?

If it is important, these are the old Muse Luxe speakers that still have the micro usb connection.

hello Hank,
So you would like to use your Muxe V1 as a simple pastrought amplifier using Aux in jack on the back?
to do so specific command needs to be sent to the ES8388 codec in HA when ther is a jack detect event.

Aux in was removed on new version on the Luxe V2 as nobody was using it, it has been replaced by headphone out + mic TTRS on the jack.

Thanks for the quick reply!
I will give it a try.

for the codec sequence you can get inspiration form this previous version of our app that was supportin aux in:

Since I am not at all familiar with esp32 and adruino.
I tried chatp gpt, gemini and cloud to get something working.
That was at least something that could be compiled but unfortunately it didn’t work.

/*--------------------------------------------------------------------------------------------------
Introduction
This program is intended to be used with the ESP32 Muse speaker, a portable and affordable bluetooth speaker that is fully programmable.
ESP32 Muse is a commercial product that can be purchase here: https://raspiaudio.com/espmuse

Features
ESP32 offers: line Input, RGB leds

This is a simplified version including only AUX in and LED functions.
--------------------------------------------------------------------------------------------------*/

#include "Audio.h"

// Standard ESP-IDF driver includes for I2C and GPIO
extern "C"
{
#include "driver/i2c.h"
#include "driver/gpio.h"
}

#include "Arduino.h"
#include <stdio.h>
#include <string.h>
#include <stdlib.h>
#include <NeoPixelBus.h>

#define muse 1

////////////////////////////////
// Pin Definitions
///////////////////////////////
#define SDA 18
#define SCL 23

//Contacts
#define PA GPIO_NUM_21 // Amp power ON
#ifdef muse
#define AUXD GPIO_NUM_27 // AUX In detect 27
#else
#define AUXD GPIO_NUM_12
#endif

////////////////////////////////
// I2C Configuration for ES8388 Codec
//////////////////////////////
#define I2C_MASTER_NUM              I2C_NUM_0
#define I2C_MASTER_FREQ_HZ          400000
#define I2C_MASTER_TIMEOUT_MS       1000

// Define I2C read/write bits for device address byte (used in hal_i2c_master_mem_write/read)
#define I2C_MASTER_WRITE_BIT        I2C_MASTER_WRITE    // for writing to slave
#define I2C_MASTER_READ_BIT         I2C_MASTER_READ     // for reading from slave


// Custom implementations of hal_i2c_master_* functions using ESP-IDF I2C driver API
esp_err_t hal_i2c_master_init(i2c_port_t i2c_num, int sda_io, int scl_io) {
    i2c_config_t conf;
    conf.mode = I2C_MODE_MASTER;
    conf.sda_io_num = sda_io;
    conf.scl_io_num = scl_io;
    conf.sda_pullup_en = GPIO_PULLUP_ENABLE;
    conf.scl_pullup_en = GPIO_PULLUP_ENABLE;
    conf.master.clk_speed = I2C_MASTER_FREQ_HZ;
    conf.clk_flags = 0; // default clk_flags is 0
    
    esp_err_t ret = i2c_param_config(i2c_num, &conf);
    if (ret != ESP_OK) return ret;
    
    return i2c_driver_install(i2c_num, conf.mode, 0, 0, 0);
}

esp_err_t hal_i2c_master_mem_write(i2c_port_t i2c_num, uint8_t device_address, 
                                 uint8_t reg_addr, uint8_t *data, size_t data_len) {
    i2c_cmd_handle_t cmd = i2c_cmd_link_create();
    i2c_master_start(cmd);
    i2c_master_write_byte(cmd, (device_address << 1) | I2C_MASTER_WRITE_BIT, true);
    i2c_master_write_byte(cmd, reg_addr, true);
    i2c_master_write(cmd, data, data_len, true);
    i2c_master_stop(cmd);
    esp_err_t ret = i2c_master_cmd_begin(i2c_num, cmd, I2C_MASTER_TIMEOUT_MS / portTICK_PERIOD_MS);
    i2c_cmd_link_delete(cmd);
    return ret;
}

esp_err_t hal_i2c_master_mem_read(i2c_port_t i2c_num, uint8_t device_address,
                                  uint8_t reg_addr, uint8_t *data, size_t data_len) {
    i2c_cmd_handle_t cmd = i2c_cmd_link_create();
    i2c_master_start(cmd);
    i2c_master_write_byte(cmd, (device_address << 1) | I2C_MASTER_WRITE_BIT, true);
    i2c_master_write_byte(cmd, reg_addr, true);
    i2c_master_start(cmd);
    i2c_master_write_byte(cmd, (device_address << 1) | I2C_MASTER_READ_BIT, true);
    i2c_master_read(cmd, data, data_len, I2C_MASTER_LAST_NACK);
    i2c_master_stop(cmd);
    esp_err_t ret = i2c_master_cmd_begin(i2c_num, cmd, I2C_MASTER_TIMEOUT_MS / portTICK_PERIOD_MS);
    i2c_cmd_link_delete(cmd);
    return ret;
}


//////////////////////////////
// NeoPixel led control
/////////////////////////////
#define PixelCount 1
#define PixelPin 22
RgbColor RED(255, 0, 0);
RgbColor GREEN(0, 255, 0);
RgbColor BLUE(0, 0, 255);
RgbColor YELLOW(255, 128, 0);
RgbColor WHITE(255, 255, 255);
RgbColor BLACK(0, 0, 0);
NeoPixelBus<NeoGrbFeature, Neo800KbpsMethod> strip(PixelCount, PixelPin);

//////////////////////////////////////////////////////////////
// init audio library
//////////////////////////////////////////////////////////////
Audio audio;

#define I2SN (i2s_port_t)0 // Still defined, but not directly used in this simplified I2S-less version

#define maxMode 3
#define btM 0
#define sdM 1
#define auxM 2
#define maxVol 50

uint8_t vauxd;
int vol, oldVol;
bool auxON = false;
bool beepON = false;
uint32_t sampleRate;
int mode = btM; // Declare mode globally and initialize

#define ES8388_ADDR 0x10

///////////////////////////////////////////////////////////////////////
// Write ES8388 register (using I2c)
///////////////////////////////////////////////////////////////////////
void ES8388_Write_Reg(uint8_t reg, uint8_t val)
{
  uint8_t buf[2];
  buf[0] = reg;
  buf[1] = val;
  hal_i2c_master_mem_write(I2C_MASTER_NUM, ES8388_ADDR, buf[0], buf + 1, 1);
}

////////////////////////////////////////////////////////////////////////
// Read ES8388 register (using I2c)
////////////////////////////////////////////////////////////////////////
uint8_t ES8388_Read_Reg( uint8_t reg_add)
{
  uint8_t val;
  hal_i2c_master_mem_read(I2C_MASTER_NUM, ES8388_ADDR, reg_add, &val, 1);
  return val;
}

////////////////////////////////////////////////////////////////////////
//
// manages volume (via vol xOUT1, vol DAC, and vol xIN2)
//
////////////////////////////////////////////////////////////////////////
void ES8388vol_Set(uint8_t volx)
{
#define M maxVol - 33

  printf("volume ==> %d\n", volx);
  ES8388_Write_Reg(25, 0x00);
  if (volx > maxVol) volx = maxVol;
  if (volx == 0)
  {
    ES8388_Write_Reg(25, 0x04);
    if (mode == auxM)
    {
      ES8388_Write_Reg(39, 0x80);
      ES8388_Write_Reg(42, 0x80);
    }
  }
  if (volx >= M)
  {
    ES8388_Write_Reg(46, volx - M);
    ES8388_Write_Reg(47, volx - M);
    ES8388_Write_Reg(26, 0x00);
    ES8388_Write_Reg(27, 0x00);
    if (mode == auxM)
    {
      uint8_t v = ((7 - (volx - M - 3) / 4) << 2) | 0xC0;
      ES8388_Write_Reg(39, v);
      ES8388_Write_Reg(42, v);
    }
  }
  else
  {
    ES8388_Write_Reg(46, 0x00);
    ES8388_Write_Reg(47, 0x00);
    ES8388_Write_Reg(26, (M - volx) * 3);
    ES8388_Write_Reg(27, (M - volx) * 3);
  }
}

//////////////////////////////////////////////////////////////////
//
// init CCODEC chip ES8388 (via I2C)
////////////////////////////////////////////////////////////////////
void ES8388_Init(void)
{
  // provides MCLK
  PIN_FUNC_SELECT(PERIPHS_IO_MUX_GPIO0_U, FUNC_GPIO0_CLK_OUT1);
  WRITE_PERI_REG(PIN_CTRL, READ_PERI_REG(PIN_CTRL) & 0xFFFFFFF0);
  // reset
  ES8388_Write_Reg(0, 0x80);
  ES8388_Write_Reg(0, 0x00);
  // mute
  ES8388_Write_Reg(25, 0x04);
  ES8388_Write_Reg(1, 0x50); //powerup
  ES8388_Write_Reg(2, 0x00);
  // slave mode
  ES8388_Write_Reg(8, 0x00);
  // DAC powerdown
  ES8388_Write_Reg(4, 0xC0);
  // vmidsel/500k ADC/DAC idem
  ES8388_Write_Reg(0, 0x12);
  ES8388_Write_Reg(1, 0x00);
  // i2s 16 bits
  ES8388_Write_Reg(23, 0x18);
  // sample freq 256
  ES8388_Write_Reg(24, 0x02);
  // LIN2/RIN2 for mixer
  ES8388_Write_Reg(38, 0x09);
  // left DAC to left mixer
  ES8388_Write_Reg(39, 0x90);
  // right DAC to right mixer
  ES8388_Write_Reg(42, 0x90);
  // DACLRC ADCLRC idem
  ES8388_Write_Reg(43, 0x80);
  ES8388_Write_Reg(45, 0x00);
  // DAC volume max
  ES8388_Write_Reg(27, 0x00);
  ES8388_Write_Reg(26, 0x00);
  ES8388_Write_Reg(2 , 0xF0);
  ES8388_Write_Reg(2 , 0x00);
  ES8388_Write_Reg(29, 0x1C); // DAC power-up LOUT1/ROUT1 enabled
  ES8388_Write_Reg(4, 0x30);
  // unmute
  ES8388_Write_Reg(25, 0x00);
  // amp validation
  gpio_set_level(PA, 1);
}

////////////////////////////////////////////////////////////////////
// annonce tiny messages (2-3 sec) (mode name)
////////////////////////////////////////////////////////////////////
void modeCall(void)
{
#define volMode 50
  char*n[] = {"/bluetooth.wav", "/player.wav", "/jack.wav"};
  ES8388vol_Set(volMode);
  printf("%d ====> %s\n", mode, n[mode]);
  // Removed playWav calls as they require SPIFFS and WAV files which are not part of AUX/LED
  beepON = false;
  ES8388vol_Set(vol);
  // i2s_set_clk is commented out or missing definition in simplified version
  // If it's necessary for operation, consider how to include it or its equivalent
  // i2s_set_clk(I2SN, sampleRate, (i2s_bits_per_sample_t)16, (i2s_channel_t)2);
}

///////////////////////////////////////////////////////////////////
//
// task managing analog input via AUXIn jack
//
///////////////////////////////////////////////////////////////////
static void aux (void* data)
{
  delay(500);
  ES8388_Write_Reg(39, 0xC0);
  ES8388_Write_Reg(42, 0xC0);
  ES8388vol_Set(45);
  while (1) {
    delay(100);
    if (mode != auxM) {
      ES8388_Write_Reg(39, 0x90);
      ES8388_Write_Reg(42, 0x90);
      auxON = 0;
      vTaskDelete(NULL);
    }
    // Check for AUX cable connection (example, requires GPIO setup for AUXD)
    vauxd = gpio_get_level(AUXD);
    if ((vauxd == 0) && (auxON == false)) {
      auxON = true;
      mode = auxM;
      modeCall();
    }
    if ((vauxd == 1) && (auxON == true)) {
      auxON = false;
      mode = btM; // Default to BT mode if AUX is disconnected
      modeCall();
    }
  }
}

void setup() {
  Serial.begin(115999);
  Serial.println("ESP32 Muse Speaker - AUX and LED only version");

  // Init LEDs
  strip.Begin();
  strip.Show(); // Initialize all pixels to 'off'

  // Initialize I2C for ES8388 codec
  hal_i2c_master_init(I2C_MASTER_NUM, SDA, SCL);
  ES8388_Init(); // Initialize the audio codec

  // Set initial volume
  vol = 30; // Default volume
  ES8388vol_Set(vol);

  // Configure AUX detection pin
  gpio_set_direction(AUXD, GPIO_MODE_INPUT);

  // Start AUX task
  xTaskCreatePinnedToCore(aux, "aux", 40000, NULL, 10, NULL, 1);

  // Initial LED color
  strip.SetPixelColor(0, BLUE);
  strip.Show();
}

void loop() {
  // Example: Change LED color based on mode
  if (mode == auxM) {
    strip.SetPixelColor(0, GREEN); // Green for AUX mode
  } else {
    strip.SetPixelColor(0, BLACK); // Off when not in AUX mode
  }
  strip.Show();

  // Basic volume control (example, needs physical buttons to be implemented)
  // For simplicity, this example doesn't include button handling
  // You would read button states here and adjust 'vol' then call ES8388vol_Set(vol);

  delay(500); // Small delay
}

Alright, I made some progress over the weekend.

Now it detects when I plug or unplug something from the AUX jack, and the LED reacts too.

But I still haven’t figured out how to get it to actually play on the Muse Luxe v1.

#include <Wire.h>
#include "driver/i2s.h"
#include <FastLED.h>

#define I2C_ADDR 0x10  // ES8388 I2C address

// Pin definitions for Muse Luxe board
#define I2C_SDA 18
#define I2C_SCL 23

#define I2S_NUM I2S_NUM_0
#define I2S_BCK_PIN  26
#define I2S_WS_PIN   25
#define I2S_DO_PIN   19    // Corrected from 22 to 19 to avoid conflict with LED pin
#define I2S_DI_PIN   21    // Only needed if input is used; otherwise can be -1

// AUX detection and LED (NeoPixel) configuration
#define PIN_AUX_DETECT 27  // AUX detect pin; LOW means AUX plugged in
#define LED_PIN 22         // NeoPixel LED connected here (working pin confirmed)
#define NUM_LEDS 1
#define LED_TYPE SK6812
#define COLOR_ORDER GRB

CRGB leds[NUM_LEDS];

// Variables for AUX state debouncing
bool auxConnected = false;   // Stable AUX connection status
bool lastAuxState = false;   // Last raw AUX detect pin reading

unsigned long lastDebounceTime = 0;
const unsigned long debounceDelay = 50;  // Debounce time in milliseconds

// Write a single byte to ES8388 register via I2C
void i2c_write_byte(uint8_t reg, uint8_t data) {
  Wire.beginTransmission(I2C_ADDR);
  Wire.write(reg);
  Wire.write(data);
  Wire.endTransmission();
}

// Initialize ES8388 codec for AUX input and DAC output
void es8388_init() {
  i2c_write_byte(0x00, 0x80); // Reset codec
  delay(10);

  i2c_write_byte(0x00, 0x00); // Normal operation mode
  i2c_write_byte(0x10, 0x00); // ADC gain unity (no amplification)
  i2c_write_byte(0x11, 0x00);
  i2c_write_byte(0x34, 0x30); // Enable ADC AUX input left + right channels
  i2c_write_byte(0x21, 0x03); // Enable DAC output left + right channels
  i2c_write_byte(0x04, 0x08); // I2S 16-bit data format
  i2c_write_byte(0x05, 0x02); // Sample rate 44.1 kHz
  i2c_write_byte(0x06, 0x00); // Master clock normal operation
  i2c_write_byte(0x20, 0xFF); // Set max volume for left DAC channel
  i2c_write_byte(0x21, 0xFF); // Set max volume for right DAC channel
}

// Initialize I2S interface for audio input/output
void i2s_init() {
  i2s_config_t i2s_config = {
    .mode = (i2s_mode_t)(I2S_MODE_MASTER | I2S_MODE_RX | I2S_MODE_TX),  // Master mode, RX and TX enabled
    .sample_rate = 44100,                     // 44.1 kHz sample rate
    .bits_per_sample = I2S_BITS_PER_SAMPLE_16BIT, // 16 bits per sample
    .channel_format = I2S_CHANNEL_FMT_RIGHT_LEFT, // Stereo channels (right + left)
    .communication_format = I2S_COMM_FORMAT_I2S_MSB, // Standard I2S MSB format
    .intr_alloc_flags = 0,                    // Default interrupt allocation
    .dma_buf_count = 8,                       // Number of DMA buffers
    .dma_buf_len = 64,                        // Size of each DMA buffer
    .use_apll = false,
    .tx_desc_auto_clear = true,
    .fixed_mclk = 0
  };

  i2s_driver_install(I2S_NUM, &i2s_config, 0, NULL);

  i2s_pin_config_t pin_config = {
    .bck_io_num = I2S_BCK_PIN,
    .ws_io_num = I2S_WS_PIN,
    .data_out_num = I2S_DO_PIN,  // Data output on GPIO19 to avoid conflict with LED
    .data_in_num = I2S_DI_PIN
  };
  i2s_set_pin(I2S_NUM, &pin_config);
}

void setup() {
  Serial.begin(115200);
  delay(1000);
  Serial.println("Setup started");

  Wire.begin(I2C_SDA, I2C_SCL);  // Start I2C with specified pins

  pinMode(PIN_AUX_DETECT, INPUT_PULLUP);  // AUX detection pin with pullup resistor

  // Initialize FastLED library for controlling NeoPixel LED
  FastLED.addLeds<LED_TYPE, LED_PIN, COLOR_ORDER>(leds, NUM_LEDS).setCorrection(TypicalLEDStrip);
  FastLED.setBrightness(50);

  leds[0] = CRGB::Blue; // Default color: Blue = AUX not connected
  FastLED.show();

  es8388_init();
  Serial.println("ES8388 initialized");

  i2s_init();
  Serial.println("I2S initialized");

  // Read initial AUX connection state (LOW = plugged in)
  auxConnected = digitalRead(PIN_AUX_DETECT) == LOW;
  lastAuxState = auxConnected;

  if (auxConnected) {
    leds[0] = CRGB::Green;  // Green LED when AUX is plugged in
  } else {
    leds[0] = CRGB::Blue;   // Blue LED when AUX not plugged in
  }
  FastLED.show();

  Serial.print("Initial AUX status: ");
  Serial.println(auxConnected ? "plugged in" : "not plugged in");
}

void loop() {
  // Read current AUX detect pin state (LOW means AUX plugged in)
  bool reading = digitalRead(PIN_AUX_DETECT) == LOW;

  // Debounce the AUX detect pin to avoid false triggers
  if (reading != lastAuxState) {
    lastDebounceTime = millis();
  }

  if ((millis() - lastDebounceTime) > debounceDelay) {
    if (reading != auxConnected) {
      auxConnected = reading;

      if (auxConnected) {
        Serial.println("AUX plugged in");
        leds[0] = CRGB::Green;  // Set LED green on AUX plug
      } else {
        Serial.println("AUX unplugged");
        leds[0] = CRGB::Blue;   // Set LED blue on AUX unplug
      }
      FastLED.show();
    }
  }

  lastAuxState = reading;

  // Audio passthrough from ADC to DAC via I2S
  const int buffer_len = 256;
  uint8_t buffer[buffer_len];
  size_t bytes_read, bytes_written;

  // Read audio data from I2S (ES8388 ADC)
  i2s_read(I2S_NUM, buffer, buffer_len, &bytes_read, portMAX_DELAY);
  // Write audio data to I2S (ES8388 DAC)
  i2s_write(I2S_NUM, buffer, bytes_read, &bytes_written, portMAX_DELAY);
}

ets Jun 8 2016 00:22:57

rst:0x1 (POWERON_RESET),boot:0x33 (SPI_FAST_FLASH_BOOT)

configsip: 0, SPIWP:0xee

clk_drv:0x00,q_drv:0x00,d_drv:0x00,cs0_drv:0x00,hd_drv:0x00,wp_drv:0x00

mode:DIO, clock div:1

load:0x3fff0030,len:4888

load:0x40078000,len:16516

load:0x40080400,len:4

load:0x40080404,len:3476

entry 0x400805b4

Setup started

ES8388 initialized

I2S initialized

Initial AUX status: not plugged in

AUX plugged in

Anyone got any ideas where I might be messing up?

Alright, got it up and running the AUX input jack now plays sound correctly, and you can adjust the volume with + and -.

It’s pretty simple and doesn’t do much else, but that’s all I wanted to achieve.

If anyone’s planning to do the same, here’s the code I’m using.

#include <Wire.h>          // FĂĽr I2C-Kommunikation mit dem ES8388
#include "driver/i2s.h"    // FĂĽr den ESP32 I2S-Treiber
#include "driver/gpio.h"   // FĂĽr allgemeine GPIO-Konfiguration
#include "driver/ledc.h"   // FĂĽr LEDC (PWM) zur MCLK-Generierung

// Definierte Pins fĂĽr den ESP32 Muse
// BITTE ĂśBERPRĂśFEN SIE DIESE PINS UNBEDINGT MIT DER DOKUMENTATION IHRES BOARDS!
#define I2S_NUM I2S_NUM_0    // Wir verwenden I2S Port 0

#define I2S_BCK_PIN    5     // I2S Bit Clock
#define I2S_WS_PIN     25    // I2S Word Select (LRCK)
#define I2S_DO_PIN     26    // I2S Data Out (vom ESP32 zum ES8388 DAC)
#define I2S_DI_PIN     35    // I2S Data In (vom ES8388 ADC zum ESP32)

#define I2C_SDA_PIN    18    // I2C Data fĂĽr ES8388 Steuerung
#define I2C_SCL_PIN    23    // I2C Clock fĂĽr ES8388 Steuerung

#define PA_AMP_ENABLE_PIN 21 // Pin zum Einschalten des Audioverstärkers (PA)
#define AUX_DETECT_PIN    27 // AUX-In-Erkennungspin (LOW = AUX angeschlossen)

#define ES8388_I2C_ADDR 0x10 // ES8388 Codec I2C Adresse

// MCLK Frequenz (44.1 kHz * 256 = 11.2896 MHz)
#define MCLK_FREQ_HZ  (11289600)
#define MCLK_GPIO     GPIO_NUM_0 // GPIO-Pin fĂĽr MCLK

int currentVolume = 40; // Anfangslautstärke (0-50 für ES8388vol_Set)

// Definierte Pins für die Lautstärketasten (gemäß speaker.txt)
#define VOL_UP_PIN GPIO_NUM_19
#define VOL_DOWN_PIN GPIO_NUM_32

// Variablen fĂĽr die Tastenentprellung
unsigned long lastButtonPressTime = 0;
const long debounceDelay = 50; // Millisekunden

// Funktion zur Steuerung der ES8388-Register ĂĽber I2C
void ES8388_Write_Reg(uint8_t reg, uint8_t val) {
  Wire.beginTransmission(ES8388_I2C_ADDR);
  Wire.write(reg);
  Wire.write(val);
  Wire.endTransmission();
  // Serial.printf("ES8388 Write: Reg 0x%02X = 0x%02X\n", reg, val); // Debugging-Ausgabe
}

// Funktion zum Lesen aus einem ES8388-Register ĂĽber I2C
uint8_t ES8388_Read_Reg(uint8_t reg_add) {
  uint8_t val = 0;
  Wire.beginTransmission(ES8388_I2C_ADDR);
  Wire.write(reg_add);
  Wire.endTransmission(false); // Sendet eine wiederholte Startbedingung
  Wire.requestFrom(ES8388_I2C_ADDR, 1);
  if (Wire.available()) {
    val = Wire.read();
  }
  // Serial.printf("ES8388 Read: Reg 0x%02X = 0x%02X\n", reg_add, val); // Debugging-Ausgabe
  return val;
}

// Steuert die Lautstärke des ES8388
// Basierend auf der Logik aus der originalen speaker.txt
void ES8388vol_Set(uint8_t volx) {
  #define M 50 - 33 // Ein Schwellenwert aus der originalen Logik (maxVol - 33)
  
  if (volx > 50) volx = 50;
  if (volx < 0) volx = 0;

  Serial.printf("Setting Volume: %d\n", volx);

  ES8388_Write_Reg(25, 0x00); // Unmute DAC vor Lautstärkeeinstellung
  
  if (volx == 0) {
    ES8388_Write_Reg(25, 0x04); // DAC mute
    ES8388_Write_Reg(39, 0x80); // Mute linker AUX-Mixer
    ES8388_Write_Reg(42, 0x80); // Mute rechter AUX-Mixer
  } else if (volx >= M) {
    ES8388_Write_Reg(46, volx - M); // Lautstärkeregister 46
    ES8388_Write_Reg(47, volx - M); // Lautstärkeregister 47
    ES8388_Write_Reg(26, 0x00); // DAC Lautstärke Max
    ES8388_Write_Reg(27, 0x00); // DAC Lautstärke Max

    uint8_t v = ((7 - (volx - M - 3) / 4) << 2) | 0xC0; // Berechnet Wert basierend auf volx
    ES8388_Write_Reg(39, v); // Linker AUX-Mixer Gain
    ES8388_Write_Reg(42, v); // Rechter AUX-Mixer Gain
  } else {
    ES8388_Write_Reg(46, 0x00); // Lautstärkeregister 46
    ES8388_Write_Reg(47, 0x00); // Lautstärkeregister 47
    ES8388_Write_Reg(26, (M - volx) * 3); // DAC Lautstärke
    ES8388_Write_Reg(27, (M - volx) * 3); // DAC Lautstärke
  }
}

// Konfiguriert den I2S-Treiber des ESP32 fĂĽr Stereo-Input/Output
void i2s_setup_driver() {
  i2s_config_t i2s_config = {
    .mode = (i2s_mode_t)(I2S_MODE_MASTER | I2S_MODE_RX | I2S_MODE_TX), // Master-Modus, Rx (Input) und Tx (Output)
    .sample_rate = 44100,                                               // 44.1 kHz
    .bits_per_sample = I2S_BITS_PER_SAMPLE_16BIT,                       // 16 Bit pro Sample
    .channel_format = I2S_CHANNEL_FMT_RIGHT_LEFT,                       // Stereo (Rechts/Links)
    .communication_format = I2S_COMM_FORMAT_I2S_MSB,                    // Standard I2S MSB Format
    .intr_alloc_flags = 0,                                              // Standard Interrupt-Allocation
    .dma_buf_count = 8,                                                 // Anzahl der DMA-Puffer
    .dma_buf_len = 64,                                                  // Größe jedes DMA-Puffers (Samples)
    .use_apll = false,                                                  // Verwenden der Standard-PLL
    .tx_desc_auto_clear = true,
    .fixed_mclk = 0 // MCLK wird separat konfiguriert
  };

  // Installiere den I2S-Treiber
  i2s_driver_install(I2S_NUM, &i2s_config, 0, NULL);

  // Konfiguriere die I2S-Pins
  i2s_pin_config_t pin_config = {
    .bck_io_num = I2S_BCK_PIN,
    .ws_io_num = I2S_WS_PIN,
    .data_out_num = I2S_DO_PIN,
    .data_in_num = I2S_DI_PIN
  };
  i2s_set_pin(I2S_NUM, &pin_config);

  Serial.println("I2S-Treiber konfiguriert.");
}

// Generiert MCLK auf GPIO0 mit dem LEDC-Peripheral (PWM)
void setup_mclk_ledc() {
    Serial.printf("Generiere MCLK von %d Hz auf GPIO%d mit LEDC...\n", MCLK_FREQ_HZ, MCLK_GPIO);

    // Konfiguriere den LEDC-Timer
    ledc_timer_config_t ledc_timer = {
        .speed_mode       = LEDC_LOW_SPEED_MODE, // Oder HIGH_SPEED_MODE, je nach Wunsch
        .duty_resolution  = LEDC_TIMER_1_BIT,    // 1 Bit Duty Resolution für 50% Tastverhältnis (ein/aus)
        .timer_num        = LEDC_TIMER_0,        // Verwende Timer 0
        .freq_hz          = MCLK_FREQ_HZ,        // Die gewĂĽnschte MCLK-Frequenz
        .clk_cfg          = LEDC_AUTO_CLK        // Auto-Clock-Selection
    };
    ledc_timer_config(&ledc_timer);

    // Konfiguriere den LEDC-Kanal
    ledc_channel_config_t ledc_channel = {
        .gpio_num         = MCLK_GPIO,           // GPIO-Pin fĂĽr MCLK
        .speed_mode       = LEDC_LOW_SPEED_MODE,
        .channel          = LEDC_CHANNEL_0,      // Verwende Kanal 0
        .intr_type        = LEDC_INTR_DISABLE,   // Keine Interrupts
        .timer_sel        = LEDC_TIMER_0,        // Wähle Timer 0
        .duty             = 1,                   // 50% Tastverhältnis (1 von 2 Schritten für 1-Bit Auflösung)
        .hpoint           = 0
    };
    ledc_channel_config(&ledc_channel);

    Serial.println("MCLK-Generierung mit LEDC konfiguriert.");
}


// Initialisiert den ES8388 Codec und konfiguriert ihn fĂĽr AUX-Eingang
// Basierend auf der ES8388_Init() und den AUX-spezifischen Teilen aus der aux() Aufgabe
void ES8388_Init_and_AUX_Config(void) {
  Serial.println("ES8388: Initialisiere Codec und AUX-Routing...");

  // Reset des ES8388
  ES8388_Write_Reg(0, 0x80); // Reset Codec
  delay(10); // Kurze Pause nach Reset
  ES8388_Write_Reg(0, 0x00); // Normaler Betriebsmodus

  // Mute den DAC während der Initialisierung
  ES8388_Write_Reg(25, 0x04); // DAC mute

  // Power Management Register
  ES8388_Write_Reg(1, 0x50); // Power up analog and digital blocks (häufiger Wert, siehe Datenblatt)
  ES8388_Write_Reg(2, 0x00); // Weitere Power-Einstellungen (Normalbetrieb)

  // System Clock & I2S Format
  ES8388_Write_Reg(8, 0x00); // Slave-Modus (ESP32 ist Master)
  ES8388_Write_Reg(23, 0x18); // I2S Data Format: 16 Bit
  ES8388_Write_Reg(24, 0x02); // Sample Rate (BCKL/LRCK): 256
                               // (Hinweis: 0x02 bedeutet BCLK_DIV=0 und DAC_OSR=2.
                               // Oft wird BCLK_DIV im Kontext von I2S und MCLK verwendet.
                               // Die 256fs Rate wird durch die MCLK_FREQ_HZ + Samplerate im ESP32 gesteuert.)


  // Analoger Eingang und Routing fĂĽr AUX
  ES8388_Write_Reg(38, 0x09); // LIN2/RIN2 für Mixer (AUX-Eingang auswählen)
  ES8388_Write_Reg(39, 0xC0); // Linker DAC zum linken Mixer (AUX_IN als Quelle)
  ES8388_Write_Reg(42, 0xC0); // Rechter DAC zum rechten Mixer (AUX_IN als Quelle)
  
  // Weitere Einstellungen aus der originalen speaker.txt
  ES8388_Write_Reg(43, 0x80); // DACLRC ADCLRC idem
  ES8388_Write_Reg(45, 0x00); // 

  // DAC Lautstärke (initial auf Max)
  ES8388_Write_Reg(27, 0x00); // DAC Lautstärke max
  ES8388_Write_Reg(26, 0x00); // DAC Lautstärke max
  
  ES8388_Write_Reg(29, 0x1C); // Weiteres Konfigurationsregister (aus speaker.txt)

  // Power up DAC Output (LOUT1/ROUT1)
  ES8388_Write_Reg(4, 0x30); // DAC Power-up LOUT1/ROUT1 aktiviert
  ES8388_Write_Reg(25, 0x00); // Unmute DAC
  
  Serial.println("ES8388: Codec konfiguriert und AUX-Routing eingestellt.");
}


void setup() {
  Serial.begin(115200);
  delay(100);
  Serial.println("ESP32 Muse AUX Input Example (LEDC MCLK, Pure I2S Driver)");

  // Initialisiere I2C fĂĽr die Kommunikation mit dem ES8388
  Wire.begin(I2C_SDA_PIN, I2C_SCL_PIN);
  Serial.println("I2C Initialisiert.");

  // Setze den Verstärker-Einschaltpin
  pinMode(PA_AMP_ENABLE_PIN, OUTPUT);
  digitalWrite(PA_AMP_ENABLE_PIN, HIGH); // Verstärker einschalten
  Serial.println("Verstärker eingeschaltet.");

  // Initialisiere den AUX-Erkennungspin
  pinMode(AUX_DETECT_PIN, INPUT_PULLUP);
  Serial.println("AUX-Erkennungspin initialisiert.");

  // Initialisiere die Lautstärketasten-Pins als Eingänge mit Pullup-Widerständen
  pinMode(VOL_UP_PIN, INPUT_PULLUP);
  pinMode(VOL_DOWN_PIN, INPUT_PULLUP);
  Serial.println("Lautstärketasten-Pins initialisiert.");


  // Generiere MCLK auf GPIO0 mit LEDC
  setup_mclk_ledc();

  // Initialisiere den I2S-Treiber des ESP32
  i2s_setup_driver();

  // Initialisiere den ES8388 Codec und konfiguriere ihn fĂĽr AUX-Eingang
  ES8388_Init_and_AUX_Config();

  // Setzen Sie die anfängliche Lautstärke
  ES8388vol_Set(currentVolume);
  Serial.printf("Anfangslautstärke eingestellt: %d\n", currentVolume);
  Serial.println("Bereit fĂĽr AUX-Audio. Steuerung: '+' fĂĽr lauter, '-' fĂĽr leiser (seriell) oder physische Tasten.");
}

void loop() {
  // ĂśberprĂĽfen des AUX-Erkennungspins (LOW = eingesteckt)
  static bool lastAuxPluggedIn = false;
  bool currentAuxPluggedIn = (digitalRead(AUX_DETECT_PIN) == LOW);

  // Debounce fĂĽr den AUX-Erkennungspin
  if (currentAuxPluggedIn != lastAuxPluggedIn) {
    delay(50); // Debounce-Zeit
    if (currentAuxPluggedIn != lastAuxPluggedIn) { // Erneute PrĂĽfung nach Debounce
      if (currentAuxPluggedIn) {
        Serial.println("AUX-Kabel eingesteckt.");
      } else {
        Serial.println("AUX-Kabel entfernt.");
      }
      lastAuxPluggedIn = currentAuxPluggedIn;
    }
  }

  // Audio Passthrough: Daten vom I2S-Eingang lesen und sofort zum I2S-Ausgang schreiben
  const int buffer_len_bytes = 256; // Puffergröße in Bytes (z.B. 64 Stereo-Samples * 2 Bytes/Sample/Kanal * 2 Kanäle)
  int16_t sample_buffer[buffer_len_bytes / sizeof(int16_t)]; // Buffer fĂĽr 16-Bit Samples
  size_t bytes_read = 0;
  size_t bytes_written = 0;

  // Audio-Daten vom ES8388 ADC (ĂĽber I2S_DI_PIN) lesen
  i2s_read(I2S_NUM, &sample_buffer, buffer_len_bytes, &bytes_read, portMAX_DELAY);

  // Audio-Daten zum ES8388 DAC (ĂĽber I2S_DO_PIN) schreiben
  if (bytes_read > 0) {
    i2s_write(I2S_NUM, &sample_buffer, bytes_read, &bytes_written, portMAX_DELAY);
  }

  // Lautstärkeregelung über Serielle Konsole
  if (Serial.available()) {
    char command = Serial.read();
    if (command == '+') {
      currentVolume = min(currentVolume + 2, 50); // Schrittweite geändert
      ES8388vol_Set(currentVolume);
    } else if (command == '-') {
      currentVolume = max(currentVolume - 2, 0); // Schrittweite geändert
      ES8388vol_Set(currentVolume);
    }
  }

  // Lautstärkeregelung über physische Tasten
  if (millis() - lastButtonPressTime > debounceDelay) {
    if (digitalRead(VOL_UP_PIN) == LOW) { // Taste gedrĂĽckt (LOW, da Pullup)
      currentVolume = min(currentVolume + 2, 50); // Schrittweite geändert
      ES8388vol_Set(currentVolume);
      lastButtonPressTime = millis();
    }
    if (digitalRead(VOL_DOWN_PIN) == LOW) { // Taste gedrĂĽckt (LOW, da Pullup)
      currentVolume = max(currentVolume - 2, 0); // Schrittweite geändert
      ES8388vol_Set(currentVolume);
      lastButtonPressTime = millis();
    }
  }

  // Eine kleine Verzögerung, um den Prozessor nicht vollständig zu blockieren
  delay(1); 
}```
1 Like

thanks for sharing, note for future reader AUX IN is only on older version of the Luxe (micro USB or blue charging led). Luxe V2 has AUX OUT + Mic mono IN on the jack.