mirror of
https://github.com/bdring/Grbl_Esp32.git
synced 2025-09-03 11:22:38 +02:00
Forgot a few pins. Fixed that. TODO FIXME: system_ini
This commit is contained in:
@@ -15,16 +15,15 @@ Global
|
|||||||
Release|x86 = Release|x86
|
Release|x86 = Release|x86
|
||||||
EndGlobalSection
|
EndGlobalSection
|
||||||
GlobalSection(ProjectConfigurationPlatforms) = postSolution
|
GlobalSection(ProjectConfigurationPlatforms) = postSolution
|
||||||
{11C8A44F-A303-4885-B5AD-5B65F7FE41C0}.Debug|x64.ActiveCfg = Grbl_Esp32\Debug|x64
|
{11C8A44F-A303-4885-B5AD-5B65F7FE41C0}.Debug|x64.ActiveCfg = Debug|x64
|
||||||
{11C8A44F-A303-4885-B5AD-5B65F7FE41C0}.Debug|x64.Build.0 = Grbl_Esp32\Debug|x64
|
{11C8A44F-A303-4885-B5AD-5B65F7FE41C0}.Debug|x64.Build.0 = Debug|x64
|
||||||
{11C8A44F-A303-4885-B5AD-5B65F7FE41C0}.Debug|x86.ActiveCfg = Grbl_Esp32\Debug|Win32
|
{11C8A44F-A303-4885-B5AD-5B65F7FE41C0}.Debug|x86.ActiveCfg = Debug|Win32
|
||||||
{11C8A44F-A303-4885-B5AD-5B65F7FE41C0}.Debug|x86.Build.0 = Grbl_Esp32\Debug|Win32
|
{11C8A44F-A303-4885-B5AD-5B65F7FE41C0}.Debug|x86.Build.0 = Debug|Win32
|
||||||
{11C8A44F-A303-4885-B5AD-5B65F7FE41C0}.Release|x64.ActiveCfg = Grbl_Esp32\Release|x64
|
{11C8A44F-A303-4885-B5AD-5B65F7FE41C0}.Release|x64.ActiveCfg = Release|x64
|
||||||
{11C8A44F-A303-4885-B5AD-5B65F7FE41C0}.Release|x64.Build.0 = Grbl_Esp32\Release|x64
|
{11C8A44F-A303-4885-B5AD-5B65F7FE41C0}.Release|x64.Build.0 = Release|x64
|
||||||
{11C8A44F-A303-4885-B5AD-5B65F7FE41C0}.Release|x86.ActiveCfg = Grbl_Esp32\Release|Win32
|
{11C8A44F-A303-4885-B5AD-5B65F7FE41C0}.Release|x86.ActiveCfg = Release|Win32
|
||||||
{11C8A44F-A303-4885-B5AD-5B65F7FE41C0}.Release|x86.Build.0 = Grbl_Esp32\Release|Win32
|
{11C8A44F-A303-4885-B5AD-5B65F7FE41C0}.Release|x86.Build.0 = Release|Win32
|
||||||
{33ECE513-60D1-4949-A4A9-C95D353C2CF0}.Debug|x64.ActiveCfg = Debug|x64
|
{33ECE513-60D1-4949-A4A9-C95D353C2CF0}.Debug|x64.ActiveCfg = Debug|x64
|
||||||
{33ECE513-60D1-4949-A4A9-C95D353C2CF0}.Debug|x64.Build.0 = Debug|x64
|
|
||||||
{33ECE513-60D1-4949-A4A9-C95D353C2CF0}.Debug|x86.ActiveCfg = Debug|Win32
|
{33ECE513-60D1-4949-A4A9-C95D353C2CF0}.Debug|x86.ActiveCfg = Debug|Win32
|
||||||
{33ECE513-60D1-4949-A4A9-C95D353C2CF0}.Debug|x86.Build.0 = Debug|Win32
|
{33ECE513-60D1-4949-A4A9-C95D353C2CF0}.Debug|x86.Build.0 = Debug|Win32
|
||||||
{33ECE513-60D1-4949-A4A9-C95D353C2CF0}.Release|x64.ActiveCfg = Release|x64
|
{33ECE513-60D1-4949-A4A9-C95D353C2CF0}.Release|x64.ActiveCfg = Release|x64
|
||||||
|
@@ -398,7 +398,7 @@ void init_motors() {
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
if (StepperResetPin->get() != Pin::Undefined) {
|
if (StepperResetPin->get() != Pin::UNDEFINED) {
|
||||||
// !RESET pin on steppers (MISO On Schematic)
|
// !RESET pin on steppers (MISO On Schematic)
|
||||||
StepperResetPin->get().setAttr(Pin::Attr::Output | Pin::Attr::InitialHigh);
|
StepperResetPin->get().setAttr(Pin::Attr::Output | Pin::Attr::InitialHigh);
|
||||||
}
|
}
|
||||||
|
@@ -138,6 +138,46 @@ const char* DYNAMIXEL_RXD_DEFAULT = DYNAMIXEL_RXD;
|
|||||||
#endif
|
#endif
|
||||||
const char* DYNAMIXEL_RTS_DEFAULT = DYNAMIXEL_RTS;
|
const char* DYNAMIXEL_RTS_DEFAULT = DYNAMIXEL_RTS;
|
||||||
|
|
||||||
|
#ifndef SPINDLE_OUTPUT_PIN
|
||||||
|
# define SPINDLE_OUTPUT_PIN "undef"
|
||||||
|
#endif
|
||||||
|
const char* SPINDLE_OUTPUT_PIN_DEFAULT = SPINDLE_OUTPUT_PIN;
|
||||||
|
|
||||||
|
#ifndef SPINDLE_ENABLE_PIN
|
||||||
|
# define SPINDLE_ENABLE_PIN "undef"
|
||||||
|
#endif
|
||||||
|
const char* SPINDLE_ENABLE_PIN_DEFAULT = SPINDLE_ENABLE_PIN;
|
||||||
|
|
||||||
|
#ifndef SPINDLE_DIRECTION_PIN
|
||||||
|
# define SPINDLE_DIRECTION_PIN "undef"
|
||||||
|
#endif
|
||||||
|
const char* SPINDLE_DIRECTION_PIN_DEFAULT = SPINDLE_DIRECTION_PIN;
|
||||||
|
|
||||||
|
#ifndef SPINDLE_FORWARD_PIN
|
||||||
|
# define SPINDLE_FORWARD_PIN "undef"
|
||||||
|
#endif
|
||||||
|
const char* SPINDLE_FORWARD_PIN_DEFAULT = SPINDLE_FORWARD_PIN;
|
||||||
|
|
||||||
|
#ifndef SPINDLE_REVERSE_PIN
|
||||||
|
# define SPINDLE_REVERSE_PIN "undef"
|
||||||
|
#endif
|
||||||
|
const char* SPINDLE_REVERSE_PIN_DEFAULT = SPINDLE_REVERSE_PIN;
|
||||||
|
|
||||||
|
#ifndef VFD_RS485_TXD_PIN
|
||||||
|
# define VFD_RS485_TXD_PIN "undef"
|
||||||
|
#endif
|
||||||
|
const char* VFD_RS485_TXD_PIN_DEFAULT = VFD_RS485_TXD_PIN;
|
||||||
|
|
||||||
|
#ifndef VFD_RS485_RXD_PIN
|
||||||
|
# define VFD_RS485_RXD_PIN "undef"
|
||||||
|
#endif
|
||||||
|
const char* VFD_RS485_RXD_PIN_DEFAULT = VFD_RS485_RXD_PIN;
|
||||||
|
|
||||||
|
#ifndef VFD_RS485_RTS_PIN
|
||||||
|
# define VFD_RS485_RTS_PIN "undef"
|
||||||
|
#endif
|
||||||
|
const char* VFD_RS485_RTS_PIN_DEFAULT = VFD_RS485_RTS_PIN;
|
||||||
|
|
||||||
#ifndef X_LIMIT_PIN
|
#ifndef X_LIMIT_PIN
|
||||||
# define X_LIMIT_PIN "undef"
|
# define X_LIMIT_PIN "undef"
|
||||||
#endif
|
#endif
|
||||||
@@ -747,6 +787,16 @@ PinSetting* DynamixelRTSPin; // DYNAMIXEL_RTS
|
|||||||
PinSetting* UserDigitalPin[4];
|
PinSetting* UserDigitalPin[4];
|
||||||
PinSetting* UserAnalogPin[4];
|
PinSetting* UserAnalogPin[4];
|
||||||
|
|
||||||
|
PinSetting* SpindleOutputPin;
|
||||||
|
PinSetting* SpindleEnablePin;
|
||||||
|
PinSetting* SpindleDirectionPin;
|
||||||
|
PinSetting* SpindleForwardPin;
|
||||||
|
PinSetting* SpindleReversePin;
|
||||||
|
|
||||||
|
PinSetting* VFDRS485TXDPin;
|
||||||
|
PinSetting* VFDRS485RXDPin;
|
||||||
|
PinSetting* VFDRS485RTSPin;
|
||||||
|
|
||||||
PinSetting* LimitPins[MAX_N_AXIS][2];
|
PinSetting* LimitPins[MAX_N_AXIS][2];
|
||||||
PinSetting* StepPins[MAX_N_AXIS][2];
|
PinSetting* StepPins[MAX_N_AXIS][2];
|
||||||
PinSetting* DirectionPins[MAX_N_AXIS][2];
|
PinSetting* DirectionPins[MAX_N_AXIS][2];
|
||||||
@@ -786,6 +836,17 @@ void make_pin_settings() {
|
|||||||
UserDigitalPin[3] = new PinSetting("Pins/UserDigital/3", USER_DIGITAL_PIN_3);
|
UserDigitalPin[3] = new PinSetting("Pins/UserDigital/3", USER_DIGITAL_PIN_3);
|
||||||
UserAnalogPin[3] = new PinSetting("Pins/UserAnalog/3", USER_ANALOG_PIN_3);
|
UserAnalogPin[3] = new PinSetting("Pins/UserAnalog/3", USER_ANALOG_PIN_3);
|
||||||
|
|
||||||
|
// Spindes:
|
||||||
|
|
||||||
|
SpindleOutputPin = new PinSetting("Pins/Spindle/Output", SPINDLE_OUTPUT_PIN);
|
||||||
|
SpindleEnablePin = new PinSetting("Pins/Spindle/Enable", SPINDLE_ENABLE_PIN);
|
||||||
|
SpindleDirectionPin = new PinSetting("Pins/Spindle/Direction", SPINDLE_DIRECTION_PIN);
|
||||||
|
SpindleForwardPin = new PinSetting("Pins/Spindle/Forward", SPINDLE_FORWARD_PIN);
|
||||||
|
SpindleReversePin = new PinSetting("Pins/Spindle/Reverse", SPINDLE_REVERSE_PIN);
|
||||||
|
VFDRS485TXDPin = new PinSetting("Pins/Spindle/RS485TXD", VFD_RS485_TXD_PIN); // VFD_RS485_TXD_PIN
|
||||||
|
VFDRS485RXDPin = new PinSetting("Pins/Spindle/RS485RXD", VFD_RS485_RXD_PIN); // VFD_RS485_RXD_PIN
|
||||||
|
VFDRS485RTSPin = new PinSetting("Pins/Spindle/RS485RTS", VFD_RS485_RTS_PIN); // VFD_RS485_RTS_PIN
|
||||||
|
|
||||||
// Axis:
|
// Axis:
|
||||||
LimitPins[X_AXIS][0] = new PinSetting("Pins/X/Limit", X_LIMIT_PIN_DEFAULT);
|
LimitPins[X_AXIS][0] = new PinSetting("Pins/X/Limit", X_LIMIT_PIN_DEFAULT);
|
||||||
LimitPins[X_AXIS][1] = new PinSetting("Pins/X2/Limit", X2_LIMIT_PIN_DEFAULT);
|
LimitPins[X_AXIS][1] = new PinSetting("Pins/X2/Limit", X2_LIMIT_PIN_DEFAULT);
|
||||||
|
@@ -272,7 +272,7 @@ void protocol_exec_rt_system() {
|
|||||||
}
|
}
|
||||||
ExecState rt_exec_state;
|
ExecState rt_exec_state;
|
||||||
rt_exec_state.value = sys_rt_exec_state.value; // Copy volatile sys_rt_exec_state.
|
rt_exec_state.value = sys_rt_exec_state.value; // Copy volatile sys_rt_exec_state.
|
||||||
if (rt_exec_state.value != 0 || cycle_stop) { // Test if any bits are on
|
if (rt_exec_state.value != 0 || cycle_stop) { // Test if any bits are on
|
||||||
// Execute system abort.
|
// Execute system abort.
|
||||||
if (rt_exec_state.bit.reset) {
|
if (rt_exec_state.bit.reset) {
|
||||||
sys.abort = true; // Only place this is set true.
|
sys.abort = true; // Only place this is set true.
|
||||||
@@ -485,21 +485,21 @@ void protocol_exec_rt_system() {
|
|||||||
// run state can be determined by checking the parser state.
|
// run state can be determined by checking the parser state.
|
||||||
if (sys_rt_exec_accessory_override.bit.coolantFloodOvrToggle) {
|
if (sys_rt_exec_accessory_override.bit.coolantFloodOvrToggle) {
|
||||||
sys_rt_exec_accessory_override.bit.coolantFloodOvrToggle = false;
|
sys_rt_exec_accessory_override.bit.coolantFloodOvrToggle = false;
|
||||||
#ifdef COOLANT_FLOOD_PIN
|
if (CoolantFloodPin->get() != Pin::UNDEFINED) {
|
||||||
if (sys.state == State::Idle || sys.state == State::Cycle || sys.state == State::Hold) {
|
if (sys.state == State::Idle || sys.state == State::Cycle || sys.state == State::Hold) {
|
||||||
gc_state.modal.coolant.Flood = !gc_state.modal.coolant.Flood;
|
gc_state.modal.coolant.Flood = !gc_state.modal.coolant.Flood;
|
||||||
coolant_set_state(gc_state.modal.coolant); // Report counter set in coolant_set_state().
|
coolant_set_state(gc_state.modal.coolant); // Report counter set in coolant_set_state().
|
||||||
|
}
|
||||||
}
|
}
|
||||||
#endif
|
|
||||||
}
|
}
|
||||||
if (sys_rt_exec_accessory_override.bit.coolantMistOvrToggle) {
|
if (sys_rt_exec_accessory_override.bit.coolantMistOvrToggle) {
|
||||||
sys_rt_exec_accessory_override.bit.coolantMistOvrToggle = false;
|
sys_rt_exec_accessory_override.bit.coolantMistOvrToggle = false;
|
||||||
#ifdef COOLANT_MIST_PIN
|
if (CoolantMistPin->get() != Pin::UNDEFINED) {
|
||||||
if (sys.state == State::Idle || sys.state == State::Cycle || sys.state == State::Hold) {
|
if (sys.state == State::Idle || sys.state == State::Cycle || sys.state == State::Hold) {
|
||||||
gc_state.modal.coolant.Mist = !gc_state.modal.coolant.Mist;
|
gc_state.modal.coolant.Mist = !gc_state.modal.coolant.Mist;
|
||||||
coolant_set_state(gc_state.modal.coolant); // Report counter set in coolant_set_state().
|
coolant_set_state(gc_state.modal.coolant); // Report counter set in coolant_set_state().
|
||||||
|
}
|
||||||
}
|
}
|
||||||
#endif
|
|
||||||
}
|
}
|
||||||
|
|
||||||
#ifdef DEBUG
|
#ifdef DEBUG
|
||||||
|
@@ -84,6 +84,18 @@ extern PinSetting* DynamixelRTSPin; // DYNAMIXEL_RTS
|
|||||||
extern PinSetting* UserDigitalPin[4];
|
extern PinSetting* UserDigitalPin[4];
|
||||||
extern PinSetting* UserAnalogPin[4];
|
extern PinSetting* UserAnalogPin[4];
|
||||||
|
|
||||||
|
// Spindle pins:
|
||||||
|
|
||||||
|
extern PinSetting* SpindleOutputPin;
|
||||||
|
extern PinSetting* SpindleEnablePin;
|
||||||
|
extern PinSetting* SpindleDirectionPin;
|
||||||
|
extern PinSetting* SpindleForwardPin;
|
||||||
|
extern PinSetting* SpindleReversePin;
|
||||||
|
|
||||||
|
extern PinSetting* VFDRS485TXDPin; // VFD_RS485_TXD_PIN
|
||||||
|
extern PinSetting* VFDRS485RXDPin; // VFD_RS485_RXD_PIN
|
||||||
|
extern PinSetting* VFDRS485RTSPin; // VFD_RS485_RTS_PIN
|
||||||
|
|
||||||
// TODO FIXME: Add motor type (enum) setting! That way we can properly hide a lot of settings, and make Motors.cpp proper!
|
// TODO FIXME: Add motor type (enum) setting! That way we can properly hide a lot of settings, and make Motors.cpp proper!
|
||||||
extern PinSetting* LimitPins[MAX_N_AXIS][2];
|
extern PinSetting* LimitPins[MAX_N_AXIS][2];
|
||||||
extern PinSetting* StepPins[MAX_N_AXIS][2];
|
extern PinSetting* StepPins[MAX_N_AXIS][2];
|
||||||
|
@@ -31,17 +31,8 @@ namespace Spindles {
|
|||||||
get_pins_and_settings(); // these gets the standard PWM settings, but many need to be changed for BESC
|
get_pins_and_settings(); // these gets the standard PWM settings, but many need to be changed for BESC
|
||||||
|
|
||||||
// a couple more pins not inherited from PWM Spindle
|
// a couple more pins not inherited from PWM Spindle
|
||||||
#ifdef SPINDLE_FORWARD_PIN
|
_forward_pin = SpindleForwardPin->get();
|
||||||
_forward_pin = SPINDLE_FORWARD_PIN;
|
_reverse_pin = SpindleReversePin->get();
|
||||||
#else
|
|
||||||
_forward_pin = Pin::UNDEFINED;
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#ifdef SPINDLE_REVERSE_PIN
|
|
||||||
_reverse_pin = SPINDLE_REVERSE_PIN;
|
|
||||||
#else
|
|
||||||
_reverse_pin = Pin::UNDEFINED;
|
|
||||||
#endif
|
|
||||||
|
|
||||||
if (_output_pin == Pin::UNDEFINED) {
|
if (_output_pin == Pin::UNDEFINED) {
|
||||||
grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "Warning: Spindle output pin not defined");
|
grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "Warning: Spindle output pin not defined");
|
||||||
|
@@ -60,27 +60,15 @@ namespace Spindles {
|
|||||||
void PWM::get_pins_and_settings() {
|
void PWM::get_pins_and_settings() {
|
||||||
// setup all the pins
|
// setup all the pins
|
||||||
|
|
||||||
#ifdef SPINDLE_OUTPUT_PIN
|
_output_pin = SpindleOutputPin->get();
|
||||||
_output_pin = SPINDLE_OUTPUT_PIN;
|
|
||||||
#else
|
|
||||||
_output_pin = Pin::UNDEFINED;
|
|
||||||
#endif
|
|
||||||
|
|
||||||
_invert_pwm = spindle_output_invert->get();
|
_invert_pwm = spindle_output_invert->get();
|
||||||
|
|
||||||
#ifdef SPINDLE_ENABLE_PIN
|
_enable_pin = SpindleEnablePin->get();
|
||||||
_enable_pin = SPINDLE_ENABLE_PIN;
|
|
||||||
#else
|
|
||||||
_enable_pin = Pin::UNDEFINED;
|
|
||||||
#endif
|
|
||||||
|
|
||||||
_off_with_zero_speed = spindle_enbl_off_with_zero_speed->get();
|
_off_with_zero_speed = spindle_enbl_off_with_zero_speed->get();
|
||||||
|
|
||||||
#ifdef SPINDLE_DIR_PIN
|
_direction_pin = SpindleDirectionPin->get();
|
||||||
_direction_pin = SPINDLE_DIR_PIN;
|
|
||||||
#else
|
|
||||||
_direction_pin = Pin::UNDEFINED;
|
|
||||||
#endif
|
|
||||||
|
|
||||||
is_reversable = (_direction_pin != Pin::UNDEFINED);
|
is_reversable = (_direction_pin != Pin::UNDEFINED);
|
||||||
|
|
||||||
|
@@ -300,26 +300,23 @@ namespace Spindles {
|
|||||||
bool VFD::get_pins_and_settings() {
|
bool VFD::get_pins_and_settings() {
|
||||||
bool pins_settings_ok = true;
|
bool pins_settings_ok = true;
|
||||||
|
|
||||||
#ifdef VFD_RS485_TXD_PIN
|
_txd_pin = VFDRS485TXDPin->get();
|
||||||
_txd_pin = VFD_RS485_TXD_PIN;
|
if (_txd_pin == Pin::UNDEFINED) {
|
||||||
#else
|
grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "Undefined VFD_RS485_TXD_PIN");
|
||||||
grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "Undefined VFD_RS485_TXD_PIN");
|
pins_settings_ok = false;
|
||||||
pins_settings_ok = false;
|
}
|
||||||
#endif
|
|
||||||
|
|
||||||
#ifdef VFD_RS485_RXD_PIN
|
_rxd_pin = VFDRS485RXDPin->get();
|
||||||
_rxd_pin = VFD_RS485_RXD_PIN;
|
if (_rxd_pin == Pin::UNDEFINED) {
|
||||||
#else
|
grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "Undefined VFD_RS485_RXD_PIN");
|
||||||
grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "Undefined VFD_RS485_RXD_PIN");
|
pins_settings_ok = false;
|
||||||
pins_settings_ok = false;
|
}
|
||||||
#endif
|
|
||||||
|
|
||||||
#ifdef VFD_RS485_RTS_PIN
|
_rts_pin = VFDRS485RTSPin->get();
|
||||||
_rts_pin = VFD_RS485_RTS_PIN;
|
if (_rts_pin == Pin::UNDEFINED) {
|
||||||
#else
|
grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "Undefined VFD_RS485_RTS_PIN");
|
||||||
grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "Undefined VFD_RS485_RTS_PIN");
|
pins_settings_ok = false;
|
||||||
pins_settings_ok = false;
|
}
|
||||||
#endif
|
|
||||||
|
|
||||||
if (laser_mode->get()) {
|
if (laser_mode->get()) {
|
||||||
grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "VFD spindle disabled in laser mode. Set $GCode/LaserMode=Off and restart");
|
grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "VFD spindle disabled in laser mode. Set $GCode/LaserMode=Off and restart");
|
||||||
|
@@ -47,6 +47,10 @@ bool debouncing = false; // debouncing in process
|
|||||||
void system_ini() { // Renamed from system_init() due to conflict with esp32 files
|
void system_ini() { // Renamed from system_init() due to conflict with esp32 files
|
||||||
// setup control inputs
|
// setup control inputs
|
||||||
|
|
||||||
|
if (ControlSafetyDoorPin->get() != Pin::UNDEFINED) {
|
||||||
|
ControlSafetyDoorPin->get().setAttr(Pin::Attr::Input | Pin::Attr::PullUp);
|
||||||
|
ControlSafetyDoorPin->get().attachInterrupt(isr_control_inputs, CHANGE);
|
||||||
|
}
|
||||||
#ifdef CONTROL_SAFETY_DOOR_PIN
|
#ifdef CONTROL_SAFETY_DOOR_PIN
|
||||||
pinMode(CONTROL_SAFETY_DOOR_PIN, INPUT_PULLUP);
|
pinMode(CONTROL_SAFETY_DOOR_PIN, INPUT_PULLUP);
|
||||||
attachInterrupt(digitalPinToInterrupt(CONTROL_SAFETY_DOOR_PIN), isr_control_inputs, CHANGE);
|
attachInterrupt(digitalPinToInterrupt(CONTROL_SAFETY_DOOR_PIN), isr_control_inputs, CHANGE);
|
||||||
@@ -130,7 +134,7 @@ void controlCheckTask(void* pvParameters) {
|
|||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
void IRAM_ATTR isr_control_inputs() {
|
void IRAM_ATTR isr_control_inputs(void*) {
|
||||||
#ifdef ENABLE_CONTROL_SW_DEBOUNCE
|
#ifdef ENABLE_CONTROL_SW_DEBOUNCE
|
||||||
// we will start a task that will recheck the switches after a small delay
|
// we will start a task that will recheck the switches after a small delay
|
||||||
int evt;
|
int evt;
|
||||||
|
@@ -197,7 +197,7 @@ ControlPins system_control_get_state();
|
|||||||
// Returns if safety door is ajar(T) or closed(F), based on pin state.
|
// Returns if safety door is ajar(T) or closed(F), based on pin state.
|
||||||
uint8_t system_check_safety_door_ajar();
|
uint8_t system_check_safety_door_ajar();
|
||||||
|
|
||||||
void isr_control_inputs();
|
void isr_control_inputs(void*);
|
||||||
|
|
||||||
// Execute the startup script lines stored in non-volatile storage upon initialization
|
// Execute the startup script lines stored in non-volatile storage upon initialization
|
||||||
void system_execute_startup(char* line);
|
void system_execute_startup(char* line);
|
||||||
|
Reference in New Issue
Block a user