diff --git a/Grbl_Esp32/src/Grbl.cpp b/Grbl_Esp32/src/Grbl.cpp index 769bd434..e04819ec 100644 --- a/Grbl_Esp32/src/Grbl.cpp +++ b/Grbl_Esp32/src/Grbl.cpp @@ -23,6 +23,7 @@ void grbl_init() { try { + settings_init(); // Load Grbl settings from non-volatile storage #ifdef USE_I2S_OUT i2s_out_init(); // The I2S out must be initialized before it can access the expanded GPIO port #endif @@ -39,7 +40,6 @@ void grbl_init() { #ifdef MACHINE_NAME report_machine_type(CLIENT_SERIAL); #endif - settings_init(); // Load Grbl settings from non-volatile storage stepper_init(); // Configure stepper pins and interrupt timers init_motors(); system_ini(); // Configure pinout pins and pin-change interrupt (Renamed due to conflict with esp32 files) diff --git a/Grbl_Esp32/src/I2SOut.cpp b/Grbl_Esp32/src/I2SOut.cpp index f2d1a1eb..1549ba31 100644 --- a/Grbl_Esp32/src/I2SOut.cpp +++ b/Grbl_Esp32/src/I2SOut.cpp @@ -958,10 +958,12 @@ int IRAM_ATTR i2s_out_init(i2s_out_init_t& init_param) { return -1 ... already initialized */ int IRAM_ATTR i2s_out_init() { + // TODO FIXME: Should check these capabilities and bail out if they don't match. + i2s_out_init_t default_param; - default_param.ws_pin = I2SOWS->get().getNative(Pin::Capabilities::Output); - default_param.bck_pin = I2SOBCK->get().getNative(Pin::Capabilities::Output); - default_param.data_pin = I2SOData->get().getNative(Pin::Capabilities::Output); + default_param.ws_pin = I2SOWS->get().getNative(Pin::Capabilities::Output | Pin::Capabilities::Native); + default_param.bck_pin = I2SOBCK->get().getNative(Pin::Capabilities::Output | Pin::Capabilities::Native); + default_param.data_pin = I2SOData->get().getNative(Pin::Capabilities::Output | Pin::Capabilities::Native); default_param.pulse_func = NULL; default_param.pulse_period = I2S_OUT_USEC_PER_PULSE; default_param.init_val = I2S_OUT_INIT_VAL;