mirror of
https://github.com/bdring/Grbl_Esp32.git
synced 2025-09-03 03:13:25 +02:00
Fixed most of the feedback from GIT (thanks gents!). SPI/I2SO should be working now. [not tested]
This commit is contained in:
@@ -19,6 +19,7 @@
|
||||
*/
|
||||
|
||||
#include "Grbl.h"
|
||||
#include "Eeprom.h"
|
||||
|
||||
void memcpy_to_eeprom_with_checksum(unsigned int destination, const char* source, unsigned int size) {
|
||||
unsigned char checksum = 0;
|
||||
|
@@ -20,7 +20,7 @@
|
||||
along with Grbl. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#include "Grbl.h"
|
||||
// #include "Grbl.h"
|
||||
|
||||
// Define EEPROM memory address location values for saved coordinate data.
|
||||
const int EEPROM_SIZE = 1024U;
|
||||
|
@@ -61,6 +61,9 @@
|
||||
#include "Pin.h"
|
||||
#include "I2SOut.h"
|
||||
|
||||
#include "Settings.h"
|
||||
#include "SettingsDefinitions.h"
|
||||
|
||||
// Always enable I2S streaming logic
|
||||
#define USE_I2S_OUT_STREAM_IMPL
|
||||
|
||||
@@ -946,15 +949,6 @@ int IRAM_ATTR i2s_out_init(i2s_out_init_t& init_param) {
|
||||
return 0;
|
||||
}
|
||||
|
||||
#ifndef I2S_OUT_WS
|
||||
# define I2S_OUT_WS GPIO_NUM_17
|
||||
#endif
|
||||
#ifndef I2S_OUT_BCK
|
||||
# define I2S_OUT_BCK GPIO_NUM_22
|
||||
#endif
|
||||
#ifndef I2S_OUT_DATA
|
||||
# define I2S_OUT_DATA GPIO_NUM_21
|
||||
#endif
|
||||
#ifndef I2S_OUT_INIT_VAL
|
||||
# define I2S_OUT_INIT_VAL 0
|
||||
#endif
|
||||
@@ -964,13 +958,13 @@ int IRAM_ATTR i2s_out_init(i2s_out_init_t& init_param) {
|
||||
return -1 ... already initialized
|
||||
*/
|
||||
int IRAM_ATTR i2s_out_init() {
|
||||
i2s_out_init_t default_param = {
|
||||
.ws_pin = I2S_OUT_WS,
|
||||
.bck_pin = I2S_OUT_BCK,
|
||||
.data_pin = I2S_OUT_DATA,
|
||||
.pulse_func = NULL,
|
||||
.pulse_period = I2S_OUT_USEC_PER_PULSE,
|
||||
.init_val = I2S_OUT_INIT_VAL,
|
||||
};
|
||||
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.pulse_func = NULL;
|
||||
default_param.pulse_period = I2S_OUT_USEC_PER_PULSE;
|
||||
default_param.init_val = I2S_OUT_INIT_VAL;
|
||||
|
||||
return i2s_out_init(default_param);
|
||||
}
|
||||
|
@@ -99,7 +99,12 @@ namespace Motors {
|
||||
|
||||
config_message();
|
||||
|
||||
SPI.begin(); // this will get called for each motor, but does not seem to hurt anything
|
||||
auto ssPin = SPISSPin->get().getNative(Pin::Capabilities::Output | Pin::Capabilities::Native);
|
||||
auto mosiPin = SPIMOSIPin->get().getNative(Pin::Capabilities::Output | Pin::Capabilities::Native);
|
||||
auto sckPin = SPISCKPin->get().getNative(Pin::Capabilities::Output | Pin::Capabilities::Native);
|
||||
auto misoPin = SPIMISOPin->get().getNative(Pin::Capabilities::Input | Pin::Capabilities::Native);
|
||||
|
||||
SPI.begin(sckPin, misoPin, mosiPin, ssPin); // this will get called for each motor, but does not seem to hurt anything
|
||||
|
||||
tmcstepper->begin();
|
||||
|
||||
|
@@ -4,7 +4,7 @@
|
||||
#include "Pins/PinOptionsParser.h"
|
||||
#include "Pins/VoidPinDetail.h"
|
||||
#include "Pins/GPIOPinDetail.h"
|
||||
#include "Pins/I2SPinDetail.h"
|
||||
#include "Pins/I2SOPinDetail.h"
|
||||
|
||||
#if defined PIN_DEBUG && defined ESP32
|
||||
# include "Pins/DebugPinDetail.h"
|
||||
@@ -83,9 +83,9 @@ bool Pin::parse(String str, Pins::PinDetail*& pinImplementation) {
|
||||
// Build this pin:
|
||||
if (prefix == "gpio") {
|
||||
pinImplementation = new Pins::GPIOPinDetail(uint8_t(pinNumber), parser);
|
||||
} else if (prefix == "i2s") {
|
||||
} else if (prefix == "i2so") {
|
||||
#ifdef ESP32
|
||||
pinImplementation = new Pins::I2SPinDetail(uint8_t(pinNumber), parser);
|
||||
pinImplementation = new Pins::I2SOPinDetail(uint8_t(pinNumber), parser);
|
||||
#else
|
||||
return false; // not supported
|
||||
#endif
|
||||
|
@@ -745,6 +745,15 @@ PinSetting* DynamixelRTSPin; // DYNAMIXEL_RTS
|
||||
PinSetting* UserDigitalPin[4];
|
||||
PinSetting* UserAnalogPin[4];
|
||||
|
||||
PinSetting* SPISSPin; // SS
|
||||
PinSetting* SPISCKPin; // SCK
|
||||
PinSetting* SPIMISOPin; // MISO
|
||||
PinSetting* SPIMOSIPin; // MOSI
|
||||
|
||||
PinSetting* I2SOBCK;
|
||||
PinSetting* I2SOWS;
|
||||
PinSetting* I2SOData;
|
||||
|
||||
PinSetting* SpindleOutputPin;
|
||||
PinSetting* SpindleEnablePin;
|
||||
PinSetting* SpindleDirectionPin;
|
||||
@@ -798,6 +807,16 @@ void make_pin_settings() {
|
||||
UserDigitalPin[3] = new PinSetting("UserDigital/3/Pin", USER_DIGITAL_PIN_3_DEFAULT);
|
||||
UserAnalogPin[3] = new PinSetting("UserAnalog/3/Pin", USER_ANALOG_PIN_3_DEFAULT);
|
||||
|
||||
// SPI pins:
|
||||
SPISSPin = new PinSetting("SPI/SS/Pin", "GPIO.5");
|
||||
SPISCKPin = new PinSetting("SPI/SCK/Pin", "GPIO.18");
|
||||
SPIMISOPin = new PinSetting("SPI/MISO/Pin", "GPIO.19");
|
||||
SPIMOSIPin = new PinSetting("SPI/MOSI/Pin", "GPIO.23");
|
||||
|
||||
I2SOBCK = new PinSetting("I2SO/BCK/Pin", "GPIO.22");
|
||||
I2SOWS = new PinSetting("I2SO/WS/Pin", "GPIO.17");
|
||||
I2SOData = new PinSetting("I2SO/DATA/Pin", "GPIO.21");
|
||||
|
||||
// Spindles:
|
||||
SpindleOutputPin = new PinSetting("Spindle/Output/Pin", SPINDLE_OUTPUT_PIN_DEFAULT);
|
||||
SpindleEnablePin = new PinSetting("Spindle/Enable/Pin", SPINDLE_ENABLE_PIN_DEFAULT);
|
||||
|
@@ -1,5 +1,5 @@
|
||||
#ifdef ESP32
|
||||
# include "I2SPinDetail.h"
|
||||
# include "I2SOPinDetail.h"
|
||||
|
||||
# include "../I2SOut.h"
|
||||
# include "../Assert.h"
|
||||
@@ -7,7 +7,7 @@
|
||||
extern "C" void __digitalWrite(uint8_t pin, uint8_t val);
|
||||
|
||||
namespace Pins {
|
||||
I2SPinDetail::I2SPinDetail(uint8_t index, const PinOptionsParser& options) :
|
||||
I2SOPinDetail::I2SOPinDetail(uint8_t index, const PinOptionsParser& options) :
|
||||
PinDetail(index), _capabilities(PinCapabilities::Output | PinCapabilities::I2S), _attributes(Pins::PinAttributes::Undefined),
|
||||
_readWriteMask(0) {
|
||||
// User defined pin capabilities
|
||||
@@ -29,20 +29,20 @@ namespace Pins {
|
||||
}
|
||||
}
|
||||
|
||||
PinCapabilities I2SPinDetail::capabilities() const { return PinCapabilities::Output | PinCapabilities::I2S; }
|
||||
PinCapabilities I2SOPinDetail::capabilities() const { return PinCapabilities::Output | PinCapabilities::I2S; }
|
||||
|
||||
void I2SPinDetail::write(int high) {
|
||||
void I2SOPinDetail::write(int high) {
|
||||
Assert(_attributes.has(PinAttributes::Output), "Pin has no output attribute defined. Cannot write to it.");
|
||||
int value = _readWriteMask ^ high;
|
||||
i2s_out_write(_index, value);
|
||||
}
|
||||
|
||||
int I2SPinDetail::read() {
|
||||
int I2SOPinDetail::read() {
|
||||
auto raw = i2s_out_read(_index);
|
||||
return raw ^ _readWriteMask;
|
||||
}
|
||||
|
||||
void I2SPinDetail::setAttr(PinAttributes value) {
|
||||
void I2SOPinDetail::setAttr(PinAttributes value) {
|
||||
// Check the attributes first:
|
||||
Assert(value.validateWith(this->_capabilities), "The requested attributes don't match the pin capabilities");
|
||||
Assert(!_attributes.conflictsWith(value), "Attributes on this pin have been set before, and there's a conflict.");
|
||||
@@ -61,7 +61,7 @@ namespace Pins {
|
||||
}
|
||||
}
|
||||
|
||||
String I2SPinDetail::toString() const { return String("I2S.") + int(_index); }
|
||||
String I2SOPinDetail::toString() const { return String("I2S.") + int(_index); }
|
||||
}
|
||||
|
||||
#endif
|
@@ -4,13 +4,13 @@
|
||||
# include "PinDetail.h"
|
||||
|
||||
namespace Pins {
|
||||
class I2SPinDetail : public PinDetail {
|
||||
class I2SOPinDetail : public PinDetail {
|
||||
PinCapabilities _capabilities;
|
||||
PinAttributes _attributes;
|
||||
int _readWriteMask;
|
||||
|
||||
public:
|
||||
I2SPinDetail(uint8_t index, const PinOptionsParser& options);
|
||||
I2SOPinDetail(uint8_t index, const PinOptionsParser& options);
|
||||
|
||||
PinCapabilities capabilities() const override;
|
||||
|
||||
@@ -21,7 +21,7 @@ namespace Pins {
|
||||
|
||||
String toString() const override;
|
||||
|
||||
~I2SPinDetail() override {}
|
||||
~I2SOPinDetail() override {}
|
||||
};
|
||||
}
|
||||
|
@@ -128,6 +128,14 @@ uint32_t sd_get_current_line_number() {
|
||||
uint8_t sd_state = SDCARD_IDLE;
|
||||
|
||||
uint8_t get_sd_state(bool refresh) {
|
||||
// Before we use the SD library, we *must* make sure SPI is properly initialized. Re-initialization
|
||||
// fortunately doesn't change any of the settings.
|
||||
auto ssPin = SPISSPin->get().getNative(Pin::Capabilities::Output | Pin::Capabilities::Native);
|
||||
auto mosiPin = SPIMOSIPin->get().getNative(Pin::Capabilities::Output | Pin::Capabilities::Native);
|
||||
auto sckPin = SPISCKPin->get().getNative(Pin::Capabilities::Output | Pin::Capabilities::Native);
|
||||
auto misoPin = SPIMISOPin->get().getNative(Pin::Capabilities::Input | Pin::Capabilities::Native);
|
||||
SPI.begin(sckPin, misoPin, mosiPin, ssPin);
|
||||
|
||||
//no need to go further if SD detect is not correct
|
||||
if (SDCardDetPin->get() != Pin::UNDEFINED) {
|
||||
if (!((SDCardDetPin->get().read() == SDCARD_DET_VAL) ? true : false)) {
|
||||
|
@@ -20,9 +20,6 @@
|
||||
#include <SD.h>
|
||||
#include <SPI.h>
|
||||
|
||||
#ifndef SDCARD_DET_PIN
|
||||
# define SDCARD_DET_PIN -1
|
||||
#endif
|
||||
const int SDCARD_DET_VAL = 0;
|
||||
|
||||
const int SDCARD_IDLE = 0;
|
||||
|
@@ -5,6 +5,8 @@
|
||||
#include <nvs.h>
|
||||
#include "WebUI/ESPResponse.h"
|
||||
|
||||
#include "Eeprom.h" // For CoordIndex
|
||||
|
||||
// Initialize the configuration subsystem
|
||||
void settings_init();
|
||||
|
||||
|
@@ -84,8 +84,17 @@ extern PinSetting* DynamixelRTSPin; // DYNAMIXEL_RTS
|
||||
extern PinSetting* UserDigitalPin[4];
|
||||
extern PinSetting* UserAnalogPin[4];
|
||||
|
||||
// Spindle pins:
|
||||
// SPI pins:
|
||||
extern PinSetting* SPISSPin; // SS
|
||||
extern PinSetting* SPISCKPin; // SCK
|
||||
extern PinSetting* SPIMISOPin; // MISO
|
||||
extern PinSetting* SPIMOSIPin; // MOSI
|
||||
|
||||
extern PinSetting* I2SOBCK;
|
||||
extern PinSetting* I2SOWS;
|
||||
extern PinSetting* I2SOData;
|
||||
|
||||
// Spindle pins:
|
||||
extern PinSetting* SpindleOutputPin;
|
||||
extern PinSetting* SpindleEnablePin;
|
||||
extern PinSetting* SpindleDirectionPin;
|
||||
|
@@ -42,7 +42,7 @@
|
||||
<ClInclude Include="Grbl_Esp32\src\Pin.h" />
|
||||
<ClInclude Include="Grbl_Esp32\src\Pins\ErrorPinDetail.h" />
|
||||
<ClInclude Include="Grbl_Esp32\src\Pins\GPIOPinDetail.h" />
|
||||
<ClInclude Include="Grbl_Esp32\src\Pins\I2SPinDetail.h" />
|
||||
<ClInclude Include="Grbl_Esp32\src\Pins\I2SOPinDetail.h" />
|
||||
<ClInclude Include="Grbl_Esp32\src\Pins\PinAttributes.h" />
|
||||
<ClInclude Include="Grbl_Esp32\src\Pins\PinCapabilities.h" />
|
||||
<ClInclude Include="Grbl_Esp32\src\Pins\PinDetail.h" />
|
||||
@@ -61,7 +61,7 @@
|
||||
<ClCompile Include="Grbl_Esp32\src\Pin.cpp" />
|
||||
<ClCompile Include="Grbl_Esp32\src\Pins\ErrorPinDetail.cpp" />
|
||||
<ClCompile Include="Grbl_Esp32\src\Pins\GPIOPinDetail.cpp" />
|
||||
<ClCompile Include="Grbl_Esp32\src\Pins\I2SPinDetail.cpp" />
|
||||
<ClCompile Include="Grbl_Esp32\src\Pins\I2SOPinDetail.cpp" />
|
||||
<ClCompile Include="Grbl_Esp32\src\Pins\PinAttributes.cpp" />
|
||||
<ClCompile Include="Grbl_Esp32\src\Pins\PinCapabilities.cpp" />
|
||||
<ClCompile Include="Grbl_Esp32\src\Pins\PinDetail.cpp" />
|
||||
|
@@ -57,9 +57,6 @@
|
||||
<ClInclude Include="Grbl_Esp32\src\Pins\GPIOPinDetail.h">
|
||||
<Filter>src\Pins</Filter>
|
||||
</ClInclude>
|
||||
<ClInclude Include="Grbl_Esp32\src\Pins\I2SPinDetail.h">
|
||||
<Filter>src\Pins</Filter>
|
||||
</ClInclude>
|
||||
<ClInclude Include="Grbl_Esp32\src\StackTrace\AssertionFailed.h">
|
||||
<Filter>src\StackTrace</Filter>
|
||||
</ClInclude>
|
||||
@@ -75,6 +72,9 @@
|
||||
<ClInclude Include="X86TestSupport\Arduino.h">
|
||||
<Filter>X86TestSupport</Filter>
|
||||
</ClInclude>
|
||||
<ClInclude Include="Grbl_Esp32\src\Pins\I2SOPinDetail.h">
|
||||
<Filter>src\Pins</Filter>
|
||||
</ClInclude>
|
||||
</ItemGroup>
|
||||
<ItemGroup>
|
||||
<ClCompile Include="Grbl_Esp32\test\TestFrameworkTest.cpp">
|
||||
@@ -83,9 +83,6 @@
|
||||
<ClCompile Include="Grbl_Esp32\test\test_main.cpp">
|
||||
<Filter>test</Filter>
|
||||
</ClCompile>
|
||||
<ClCompile Include="Grbl_Esp32\test\TestFactory.cpp">
|
||||
<Filter>test</Filter>
|
||||
</ClCompile>
|
||||
<ClCompile Include="Grbl_Esp32\test\Pins\Error.cpp">
|
||||
<Filter>test\Pins</Filter>
|
||||
</ClCompile>
|
||||
@@ -125,9 +122,6 @@
|
||||
<ClCompile Include="Grbl_Esp32\src\Pins\GPIOPinDetail.cpp">
|
||||
<Filter>src\Pins</Filter>
|
||||
</ClCompile>
|
||||
<ClCompile Include="Grbl_Esp32\src\Pins\I2SPinDetail.cpp">
|
||||
<Filter>src\Pins</Filter>
|
||||
</ClCompile>
|
||||
<ClCompile Include="Grbl_Esp32\src\StackTrace\AssertionFailed.cpp">
|
||||
<Filter>src\StackTrace</Filter>
|
||||
</ClCompile>
|
||||
@@ -146,6 +140,12 @@
|
||||
<ClCompile Include="Grbl_Esp32\test\Pins\PinOptionParsing.cpp">
|
||||
<Filter>test\Pins</Filter>
|
||||
</ClCompile>
|
||||
<ClCompile Include="Grbl_Esp32\test\TestFactory.cpp">
|
||||
<Filter>test</Filter>
|
||||
</ClCompile>
|
||||
<ClCompile Include="Grbl_Esp32\src\Pins\I2SOPinDetail.cpp">
|
||||
<Filter>src\Pins</Filter>
|
||||
</ClCompile>
|
||||
</ItemGroup>
|
||||
<ItemGroup>
|
||||
<None Include="Grbl_Esp32\test\UnitTests.md">
|
||||
|
Reference in New Issue
Block a user