mirror of
https://github.com/bdring/Grbl_Esp32.git
synced 2025-09-01 02:21:46 +02:00
WIP mostly Serial port issues
This commit is contained in:
@@ -22,11 +22,10 @@
|
||||
# include "src/Grbl.h"
|
||||
|
||||
void setup() {
|
||||
// # ifdef PIN_DEBUG
|
||||
// # ifdef PIN_DEBUG
|
||||
delay(2000);
|
||||
// # endif
|
||||
// # endif
|
||||
|
||||
Serial.begin(115200);
|
||||
grbl_init();
|
||||
}
|
||||
|
||||
|
@@ -4,8 +4,10 @@ board: Debug-board
|
||||
axes:
|
||||
number_axis: 3
|
||||
|
||||
laser_mode: true
|
||||
|
||||
coolant:
|
||||
flood: gpio.26:low
|
||||
|
||||
probe:
|
||||
pin: gpio.12
|
||||
pin: gpio.12:high:pu
|
||||
|
@@ -25,16 +25,15 @@
|
||||
|
||||
void grbl_init() {
|
||||
try {
|
||||
Serial.println("Initializing WiFi...");
|
||||
client_init(); // Setup serial baud rate and interrupts
|
||||
|
||||
grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "Initializing WiFi...");
|
||||
WiFi.persistent(false);
|
||||
WiFi.disconnect(true);
|
||||
WiFi.enableSTA(false);
|
||||
WiFi.enableAP(false);
|
||||
WiFi.mode(WIFI_OFF);
|
||||
|
||||
Serial.println("Initializing serial communications...");
|
||||
// Setup serial baud rate and interrupts
|
||||
client_init();
|
||||
display_init();
|
||||
grbl_msg_sendf(
|
||||
CLIENT_SERIAL, MsgLevel::Info, "Grbl_ESP32 Ver %s Date %s", GRBL_VERSION, GRBL_VERSION_BUILD); // print grbl_esp32 verion info
|
||||
@@ -46,24 +45,24 @@ void grbl_init() {
|
||||
#endif
|
||||
|
||||
// Load Grbl settings from non-volatile storage
|
||||
Serial.println("Initializing settings...");
|
||||
grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "Initializing settings...");
|
||||
settings_init();
|
||||
MachineConfig::instance()->load();
|
||||
|
||||
#ifdef USE_I2S_OUT
|
||||
Serial.println("Initializing I2SO...");
|
||||
grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "Initializing I2SO...");
|
||||
// The I2S out must be initialized before it can access the expanded GPIO port. Must be initialized _after_ settings!
|
||||
i2s_out_init();
|
||||
#endif
|
||||
|
||||
Serial.println("Initializing steppers...");
|
||||
grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "Initializing steppers...");
|
||||
stepper_init(); // Configure stepper pins and interrupt timers
|
||||
|
||||
Serial.println("Initializing axes...");
|
||||
grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "Initializing axes...");
|
||||
MachineConfig::instance()->_axes->read_settings();
|
||||
MachineConfig::instance()->_axes->init();
|
||||
|
||||
Serial.println("Initializing system...");
|
||||
grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "Initializing system...");
|
||||
system_ini(); // Configure pinout pins and pin-change interrupt (Renamed due to conflict with esp32 files)
|
||||
memset(sys_position, 0, sizeof(sys_position)); // Clear machine position.
|
||||
|
||||
@@ -87,15 +86,15 @@ void grbl_init() {
|
||||
sys.state = State::Alarm;
|
||||
}
|
||||
#endif
|
||||
Serial.println("Initializing spindle...");
|
||||
grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "Initializing spindle...");
|
||||
Spindles::Spindle::select();
|
||||
|
||||
Serial.println("Initializing WiFi-config...");
|
||||
grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "Initializing WiFi-config...");
|
||||
#ifdef ENABLE_WIFI
|
||||
WebUI::wifi_config.begin();
|
||||
#endif
|
||||
|
||||
Serial.println("Initializing Bluetooth...");
|
||||
grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "Initializing Bluetooth...");
|
||||
#ifdef ENABLE_BLUETOOTH
|
||||
WebUI::bt_config.begin();
|
||||
#endif
|
||||
@@ -104,7 +103,7 @@ void grbl_init() {
|
||||
// This means something is terribly broken:
|
||||
|
||||
// Should grbl_sendf always work? Serial is initialized first, so after line 34 it should.
|
||||
grbl_msg_sendf(CLIENT_ALL, MsgLevel::Error, "Critical error in run_once: %s", ex.stackTrace.c_str());
|
||||
grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "Critical error in run_once: %s", ex.stackTrace.c_str());
|
||||
sleep(10000);
|
||||
throw;
|
||||
}
|
||||
|
@@ -289,7 +289,7 @@ size_t Axes::findAxisGanged(const Motors::Motor* const motor) const {
|
||||
void Axes::validate() const {}
|
||||
|
||||
void Axes::handle(Configuration::HandlerBase& handler) {
|
||||
handler.handle("_numberAxis", _numberAxis);
|
||||
handler.handle("number_axis", _numberAxis);
|
||||
|
||||
const char* allAxis = "xyzabc";
|
||||
|
||||
|
@@ -36,115 +36,3 @@
|
||||
*/
|
||||
|
||||
#define MACHINE_NAME "Test Drive - Demo Only No I/O!"
|
||||
|
||||
|
||||
#define N_AXIS 3
|
||||
// This cannot use homing because there are no switches
|
||||
#ifdef DEFAULT_HOMING_CYCLE_0
|
||||
#undef DEFAULT_HOMING_CYCLE_0
|
||||
#endif
|
||||
|
||||
#ifdef DEFAULT_HOMING_CYCLE_1
|
||||
#undef DEFAULT_HOMING_CYCLE_1
|
||||
#endif
|
||||
|
||||
|
||||
#ifdef USE_RMT_STEPS
|
||||
#undef USE_RMT_STEPS // Suppress unused variable warning
|
||||
#endif
|
||||
|
||||
|
||||
// Output devices:
|
||||
// - I2S
|
||||
|
||||
#define USE_I2S_OUT
|
||||
#define USE_I2S_STEPS
|
||||
// #define I2S_OUT_BCK "gpio.22"
|
||||
// #define I2S_OUT_WS "gpio.17"
|
||||
// #define I2S_OUT_DATA "gpio.21"
|
||||
|
||||
#define COOLANT_MIST_PIN "i2so.24"
|
||||
|
||||
// x CoolantControl
|
||||
|
||||
// #define COOLANT_MIST_PIN "gpio.2"
|
||||
// #define COOLANT_FLOOD_PIN "gpio.4"
|
||||
|
||||
// x StandardStepper
|
||||
|
||||
// #define X_STEP_PIN "gpio.2"
|
||||
// #define X_DIRECTION_PIN "gpio.4"
|
||||
// #define X_DISABLE_PIN "gpio.16"
|
||||
|
||||
// x Unipolar
|
||||
|
||||
// #define X_UNIPOLAR
|
||||
// #define X_PIN_PHASE_0 "gpio.2"
|
||||
// #define X_PIN_PHASE_1 "gpio.4"
|
||||
// #define X_PIN_PHASE_2 "gpio.16"
|
||||
// #define X_PIN_PHASE_3 "gpio.15"
|
||||
|
||||
// Spindles:
|
||||
|
||||
#define SPINDLE_TYPE SpindleType::NONE
|
||||
|
||||
// #define SPINDLE_OUTPUT_PIN "gpio.15"
|
||||
// #define SPINDLE_ENABLE_PIN "gpio.2"
|
||||
// #define SPINDLE_DIRECTION_PIN "gpio.4"
|
||||
// #define SPINDLE_FORWARD_PIN "gpio.16"
|
||||
// #define SPINDLE_REVERSE_PIN "gpio.17"
|
||||
|
||||
// x 10V
|
||||
// #define SPINDLE_TYPE SpindleType::_10V
|
||||
|
||||
// x PWM
|
||||
// #define SPINDLE_TYPE SpindleType::PWM
|
||||
|
||||
// x Relay
|
||||
// #define SPINDLE_TYPE SpindleType::RELAY
|
||||
|
||||
// - BESC
|
||||
// - DAC
|
||||
//
|
||||
// x User Digital pins
|
||||
// #define USER_DIGITAL_PIN_0 "gpio.15"
|
||||
// #define USER_DIGITAL_PIN_1 "gpio.2"
|
||||
// #define USER_DIGITAL_PIN_2 "gpio.4"
|
||||
// #define USER_DIGITAL_PIN_3 "gpio.16"
|
||||
|
||||
// x User Analog pins
|
||||
// #define USER_ANALOG_PIN_0 "gpio.15"
|
||||
// #define USER_ANALOG_PIN_1 "gpio.2"
|
||||
// #define USER_ANALOG_PIN_2 "gpio.4"
|
||||
// #define USER_ANALOG_PIN_3 "gpio.16"
|
||||
|
||||
//
|
||||
// Input devices :
|
||||
// x Probe
|
||||
// #define PROBE_PIN "gpio.18:pu"
|
||||
|
||||
// x Limits
|
||||
// #define X_LIMIT_PIN "gpio.18:pu"
|
||||
// x System : ControlSafetyDoor
|
||||
// #define CONTROL_SAFETY_DOOR_PIN "gpio.22:pu"
|
||||
// x System : ControlReset
|
||||
// #define CONTROL_RESET_PIN "gpio.23:pu"
|
||||
// x System : ControlFeedHold
|
||||
// #define CONTROL_FEED_HOLD_PIN "gpio.22:pu"
|
||||
// x System : ControlCycleStart
|
||||
// #define CONTROL_CYCLE_START_PIN "gpio.18:pu"
|
||||
// - System : Macro0
|
||||
// - System : Macro1
|
||||
// - System : Macro2
|
||||
// - System : Macro3
|
||||
//
|
||||
// Uart devices :
|
||||
// - Dynamixel
|
||||
// - H2ASpindle
|
||||
// - HuanyangSpindle
|
||||
//
|
||||
// Other :
|
||||
// - RcServo
|
||||
// x SDCard
|
||||
// x Trinamic
|
||||
|
||||
|
@@ -91,7 +91,7 @@ void client_init() {
|
||||
xTaskCreatePinnedToCore(heapCheckTask, "heapTask", 2000, NULL, 1, NULL, 1);
|
||||
#endif
|
||||
|
||||
Uart0.setPins(1, 3); // Tx 1, Rx 3 - standard hardware pins
|
||||
Uart0.setPins(GPIO_NUM_1, GPIO_NUM_3); // Tx 1, Rx 3 - standard hardware pins
|
||||
Uart0.begin(BAUD_RATE, Uart::Data::Bits8, Uart::Stop::Bits1, Uart::Parity::None);
|
||||
|
||||
client_reset_read_buffer(CLIENT_ALL);
|
||||
|
Reference in New Issue
Block a user