Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

new initPin() function that displays messages #648

Open
wants to merge 1 commit into
base: Devt
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
4 changes: 2 additions & 2 deletions Grbl_Esp32/Custom/atari_1020.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -48,8 +48,8 @@ void machine_init() {
solenoid_pwm_chan_num = sys_get_next_PWM_chan_num();
ledcSetup(solenoid_pwm_chan_num, SOLENOID_PWM_FREQ, SOLENOID_PWM_RES_BITS);
ledcAttachPin(SOLENOID_PEN_PIN, solenoid_pwm_chan_num);
pinMode(SOLENOID_DIRECTION_PIN, OUTPUT); // this sets the direction of the solenoid current
pinMode(REED_SW_PIN, INPUT_PULLUP); // external pullup required
initPin(SOLENOID_DIRECTION_PIN, OUTPUT, "Solenoid"); // this sets the direction of the solenoid current
initPin(REED_SW_PIN, INPUT_PULLUP, "Reed Switch"); // external pullup required
// setup a task that will calculate solenoid position
xTaskCreatePinnedToCore(solenoidSyncTask, // task
"solenoidSyncTask", // name for task
Expand Down
3 changes: 1 addition & 2 deletions Grbl_Esp32/Custom/mpcnc_laser_module.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -28,8 +28,7 @@ special things your machine needs at startup.
*/
void machine_init() {
// force this on all the time
grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "Custom machine_init() Level Shift Enabled");
pinMode(LVL_SHIFT_ENABLE, OUTPUT);
initPin(LVL_SHIFT_ENABLE, OUTPUT, "Level Shift");
digitalWrite(LVL_SHIFT_ENABLE, HIGH);
}
#endif
4 changes: 2 additions & 2 deletions Grbl_Esp32/src/CoolantControl.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -25,10 +25,10 @@

void coolant_init() {
#ifdef COOLANT_FLOOD_PIN
pinMode(COOLANT_FLOOD_PIN, OUTPUT);
initPin(COOLANT_FLOOD_PIN, OUTPUT, "Flood coolant");
#endif
#ifdef COOLANT_MIST_PIN
pinMode(COOLANT_MIST_PIN, OUTPUT);
initPin(COOLANT_MIST_PIN, OUTPUT, "Mist coolant");
#endif
coolant_stop();
}
Expand Down
3 changes: 3 additions & 0 deletions Grbl_Esp32/src/Grbl.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -21,6 +21,8 @@
#include "Grbl.h"
#include <WiFi.h>

bool reinit = false;

void grbl_init() {
#ifdef USE_I2S_OUT
i2s_out_init(); // The I2S out must be initialized before it can access the expanded GPIO port
Expand Down Expand Up @@ -73,6 +75,7 @@ void grbl_init() {
WebUI::bt_config.begin();
#endif
WebUI::inputBuffer.begin();
reinit = true; // This can be used to make messages appear only once
}

static void reset_variables() {
Expand Down
4 changes: 4 additions & 0 deletions Grbl_Esp32/src/Grbl.h
Original file line number Diff line number Diff line change
Expand Up @@ -89,6 +89,10 @@ const char* const GRBL_VERSION_BUILD = "20201015";

#include "I2SOut.h"

// reinit can be used to suppress duplicate message on reinitialization
// Initially false, then set to true after first init()
extern bool reinit;

void grbl_init();
void run_once();

Expand Down
2 changes: 1 addition & 1 deletion Grbl_Esp32/src/Limits.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -321,7 +321,7 @@ void limits_init() {
for (int gang_index = 0; gang_index < 2; gang_index++) {
uint8_t pin;
if ((pin = limit_pins[axis][gang_index]) != UNDEFINED_PIN) {
pinMode(pin, mode);
initPin(pin, mode, axis, gang_index, "Limit");
limit_mask |= bit(axis);
if (hard_limits->get()) {
attachInterrupt(pin, isr_limit_switches, CHANGE);
Expand Down
7 changes: 3 additions & 4 deletions Grbl_Esp32/src/Motors/Motors.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -253,22 +253,21 @@ void init_motors() {
uint8_t pin = ms3_pins[axis][gang_index];
if (pin != UNDEFINED_PIN) {
digitalWrite(pin, HIGH);
pinMode(pin, OUTPUT);
initPin(pin, OUTPUT, axis, gang_index, "StepStick MS3");
}
}
}

# ifdef STEPPER_RESET
// !RESET pin on steppers (MISO On Schematic)
digitalWrite(STEPPER_RESET, HIGH);
pinMode(STEPPER_RESET, OUTPUT);
initPin(STEPPER_RESET, OUTPUT, "Stepper Reset");
# endif

#endif

if (STEPPERS_DISABLE_PIN != UNDEFINED_PIN) {
pinMode(STEPPERS_DISABLE_PIN, OUTPUT); // global motor enable pin
grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "Global stepper disable pin:%s", pinName(STEPPERS_DISABLE_PIN));
initPin(STEPPERS_DISABLE_PIN, OUTPUT, "Global stepper disable"); // global motor enable pin
}

// certain motors need features to be turned on. Check them here
Expand Down
6 changes: 3 additions & 3 deletions Grbl_Esp32/src/Motors/StandardStepper.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -51,7 +51,7 @@ namespace Motors {
void StandardStepper::init_step_dir_pins() {
_invert_step_pin = bitnum_istrue(step_invert_mask->get(), _axis_index);
_invert_dir_pin = bitnum_istrue(dir_invert_mask->get(), _axis_index);
pinMode(_dir_pin, OUTPUT);
initPin(_dir_pin, OUTPUT, _axis_index, _dual_axis_index, "Direction");

#ifdef USE_RMT_STEPS
rmtConfig.rmt_mode = RMT_MODE_TX;
Expand Down Expand Up @@ -88,10 +88,10 @@ namespace Motors {
rmt_fill_tx_items(rmtConfig.channel, &rmtItem[0], rmtConfig.mem_block_num, 0);

#else
pinMode(_step_pin, OUTPUT);
initPin(_step_pin, OUTPUT, _axis_index, _dual_axis_index, "Step");

#endif // USE_RMT_STEPS
pinMode(_disable_pin, OUTPUT);
initPin(_disable_pin, OUTPUT, _axis_index, _dual_axis_index, "Disable");
}

void StandardStepper::config_message() {
Expand Down
2 changes: 1 addition & 1 deletion Grbl_Esp32/src/Motors/TrinamicDriver.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -71,7 +71,7 @@ namespace Motors {
init_step_dir_pins(); // from StandardStepper

digitalWrite(_cs_pin, HIGH);
pinMode(_cs_pin, OUTPUT);
initPin(_cs_pin, OUTPUT, _axis_index, _dual_axis_index, "Trinamic CS");

// use slower speed if I2S
if (_cs_pin >= I2S_OUT_PIN_BASE) {
Expand Down
8 changes: 4 additions & 4 deletions Grbl_Esp32/src/Motors/UnipolarMotor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -9,10 +9,10 @@ namespace Motors {
{}

void UnipolarMotor::init() {
pinMode(_pin_phase0, OUTPUT);
pinMode(_pin_phase1, OUTPUT);
pinMode(_pin_phase2, OUTPUT);
pinMode(_pin_phase3, OUTPUT);
initPin(_pin_phase0, OUTPUT, _axis_index, _dual_axis_index, "Phase0");
initPin(_pin_phase1, OUTPUT, _axis_index, _dual_axis_index, "Phase1");
initPin(_pin_phase2, OUTPUT, _axis_index, _dual_axis_index, "Phase2");
initPin(_pin_phase3, OUTPUT, _axis_index, _dual_axis_index, "Phase3");
_current_phase = 0;
config_message();
}
Expand Down
33 changes: 33 additions & 0 deletions Grbl_Esp32/src/Pins.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -54,3 +54,36 @@ int IRAM_ATTR digitalRead(uint8_t pin) {
return 0;
#endif
}

// For pins that are not associated with an axis
void initPin(uint8_t pin, uint8_t mode, const char *name) {
if (!reinit) {
grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "%s on pin %s", name, pinName(pin).c_str());
pinMode(pin, mode);
}
}

// For pins that are associated with an non-gangeable axis
void initPin(uint8_t pin, uint8_t mode, uint8_t axis, const char *name) {
if (!reinit) {
grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "%s %s on pin %s", reportAxisNameMsg(axis), name, pinName(pin).c_str());
pinMode(pin, mode);
}
}

// For pins that are associated with a gangeable axis
void initPin(uint8_t pin, uint8_t mode, uint8_t axis, uint8_t gang, const char *name) {
if (!reinit) {
grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "%s %s on pin %s", reportAxisNameMsg(axis, gang), name, pinName(pin).c_str());
pinMode(pin, mode);
}
}

// For arrays of pins such as user digital pins
void initPin(uint8_t pin, uint8_t mode, const char *name, int n) {
if (!reinit) {
grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "%s:%d on pin %s", name, n, pinName(pin).c_str());
pinMode(pin, mode);
}
}

5 changes: 5 additions & 0 deletions Grbl_Esp32/src/Pins.h
Original file line number Diff line number Diff line change
Expand Up @@ -9,4 +9,9 @@ extern "C" int __digitalRead(uint8_t pin);
extern "C" void __pinMode(uint8_t pin, uint8_t mode);
extern "C" void __digitalWrite(uint8_t pin, uint8_t val);

void initPin(uint8_t pin, uint8_t mode, const char *name);
void initPin(uint8_t pin, uint8_t mode, uint8_t axis, const char *name);
void initPin(uint8_t pin, uint8_t mode, uint8_t axis, uint8_t gang, const char *name);
void initPin(uint8_t pin, uint8_t mode, const char *name, int n);

String pinName(uint8_t pin);
10 changes: 2 additions & 8 deletions Grbl_Esp32/src/Probe.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -28,19 +28,13 @@ static bool is_probe_away;

// Probe pin initialization routine.
void probe_init() {
static bool show_init_msg = true; // used to show message only once.

if (PROBE_PIN != UNDEFINED_PIN) {
#ifdef DISABLE_PROBE_PIN_PULL_UP
pinMode(PROBE_PIN, INPUT);
initPin(PROBE_PIN, INPUT, "Probe");
#else
pinMode(PROBE_PIN, INPUT_PULLUP); // Enable internal pull-up resistors. Normal high operation.
initPin(PROBE_PIN, INPUT_PULLUP, "Probe"); // Enable internal pull-up resistors. Normal high operation.
#endif

if (show_init_msg) {
grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "Probe on pin %s", pinName(PROBE_PIN).c_str());
show_init_msg = false;
}
}
}

Expand Down
17 changes: 1 addition & 16 deletions Grbl_Esp32/src/Report.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -903,22 +903,7 @@ void report_hex_msg(uint8_t* buf, const char* prefix, int len) {
}

char report_get_axis_letter(uint8_t axis) {
switch (axis) {
case X_AXIS:
return 'X';
case Y_AXIS:
return 'Y';
case Z_AXIS:
return 'Z';
case A_AXIS:
return 'A';
case B_AXIS:
return 'B';
case C_AXIS:
return 'C';
default:
return '?';
}
return axis > C_AXIS ? '?' : "XYZABC"[axis];
}

char* reportAxisLimitsMsg(uint8_t axis) {
Expand Down
8 changes: 4 additions & 4 deletions Grbl_Esp32/src/Spindles/10vSpindle.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -51,10 +51,10 @@ namespace Spindles {
ledcSetup(_pwm_chan_num, (double)_pwm_freq, _pwm_precision); // setup the channel
ledcAttachPin(_output_pin, _pwm_chan_num); // attach the PWM to the pin

pinMode(_enable_pin, OUTPUT);
pinMode(_direction_pin, OUTPUT);
pinMode(_forward_pin, OUTPUT);
pinMode(_reverse_pin, OUTPUT);
initPin(_enable_pin, OUTPUT, "10V Spindle Enable");
initPin(_direction_pin, OUTPUT, "10V Spindle Direction");
initPin(_forward_pin, OUTPUT, "10V Spindle Forward");
initPin(_reverse_pin, OUTPUT, "10V Spindle Reverse");

set_rpm(0);

Expand Down
2 changes: 1 addition & 1 deletion Grbl_Esp32/src/Spindles/BESCSpindle.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -71,7 +71,7 @@ namespace Spindles {
ledcSetup(_pwm_chan_num, (double)_pwm_freq, _pwm_precision); // setup the channel
ledcAttachPin(_output_pin, _pwm_chan_num); // attach the PWM to the pin

pinMode(_enable_pin, OUTPUT);
initPin(_enable_pin, OUTPUT, "BESC Spindle Enable");

set_rpm(0);

Expand Down
5 changes: 3 additions & 2 deletions Grbl_Esp32/src/Spindles/DacSpindle.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -44,8 +44,9 @@ namespace Spindles {
return;
}

pinMode(_enable_pin, OUTPUT);
pinMode(_direction_pin, OUTPUT);
// XXX need message for output pin
initPin(_enable_pin, OUTPUT, "DAC Spindle Enable");
initPin(_direction_pin, OUTPUT, "DAC Spindle Direction");

is_reversable = (_direction_pin != UNDEFINED_PIN);
use_delays = true;
Expand Down
4 changes: 2 additions & 2 deletions Grbl_Esp32/src/Spindles/PWMSpindle.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -46,8 +46,8 @@ namespace Spindles {
ledcSetup(_pwm_chan_num, (double)_pwm_freq, _pwm_precision); // setup the channel
ledcAttachPin(_output_pin, _pwm_chan_num); // attach the PWM to the pin

pinMode(_enable_pin, OUTPUT);
pinMode(_direction_pin, OUTPUT);
initPin(_enable_pin, OUTPUT, "PWM Spindle Enable");
initPin(_direction_pin, OUTPUT, "PWM Spindle Direction");

use_delays = true;

Expand Down
6 changes: 3 additions & 3 deletions Grbl_Esp32/src/Spindles/RelaySpindle.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -34,9 +34,9 @@ namespace Spindles {
return;
}

pinMode(_output_pin, OUTPUT);
pinMode(_enable_pin, OUTPUT);
pinMode(_direction_pin, OUTPUT);
initPin(_output_pin, OUTPUT, "Relay Spindle Output");
initPin(_enable_pin, OUTPUT, "Relay Spindle Enable");
initPin(_direction_pin, OUTPUT, "Relay Spindle Direction");

is_reversable = (_direction_pin != UNDEFINED_PIN);
use_delays = true;
Expand Down
20 changes: 8 additions & 12 deletions Grbl_Esp32/src/System.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -47,39 +47,35 @@ void system_ini() { // Renamed from system_init() due to conflict with esp32 fi
// setup control inputs

#ifdef CONTROL_SAFETY_DOOR_PIN
pinMode(CONTROL_SAFETY_DOOR_PIN, INPUT_PULLUP);
initPin(CONTROL_SAFETY_DOOR_PIN, INPUT_PULLUP, "Safety Door");
attachInterrupt(digitalPinToInterrupt(CONTROL_SAFETY_DOOR_PIN), isr_control_inputs, CHANGE);
#endif
#ifdef CONTROL_RESET_PIN
pinMode(CONTROL_RESET_PIN, INPUT_PULLUP);
initPin(CONTROL_RESET_PIN, INPUT_PULLUP, "Reset");
attachInterrupt(digitalPinToInterrupt(CONTROL_RESET_PIN), isr_control_inputs, CHANGE);
#endif
#ifdef CONTROL_FEED_HOLD_PIN
pinMode(CONTROL_FEED_HOLD_PIN, INPUT_PULLUP);
initPin(CONTROL_FEED_HOLD_PIN, INPUT_PULLUP, "Feed Hold");
attachInterrupt(digitalPinToInterrupt(CONTROL_FEED_HOLD_PIN), isr_control_inputs, CHANGE);
#endif
#ifdef CONTROL_CYCLE_START_PIN
pinMode(CONTROL_CYCLE_START_PIN, INPUT_PULLUP);
initPin(CONTROL_CYCLE_START_PIN, INPUT_PULLUP, "Cycle Start");
attachInterrupt(digitalPinToInterrupt(CONTROL_CYCLE_START_PIN), isr_control_inputs, CHANGE);
#endif
#ifdef MACRO_BUTTON_0_PIN
grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "Macro Pin 0");
pinMode(MACRO_BUTTON_0_PIN, INPUT_PULLUP);
initPin(MACRO_BUTTON_0_PIN, INPUT_PULLUP, "Macro Pin 0");
attachInterrupt(digitalPinToInterrupt(MACRO_BUTTON_0_PIN), isr_control_inputs, CHANGE);
#endif
#ifdef MACRO_BUTTON_1_PIN
grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "Macro Pin 1");
pinMode(MACRO_BUTTON_1_PIN, INPUT_PULLUP);
initPin(MACRO_BUTTON_1_PIN, INPUT_PULLUP, "Macro Pin 1");
attachInterrupt(digitalPinToInterrupt(MACRO_BUTTON_1_PIN), isr_control_inputs, CHANGE);
#endif
#ifdef MACRO_BUTTON_2_PIN
grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "Macro Pin 2");
pinMode(MACRO_BUTTON_2_PIN, INPUT_PULLUP);
initPin(MACRO_BUTTON_2_PIN, INPUT_PULLUP, "Macro Pin 2");
attachInterrupt(digitalPinToInterrupt(MACRO_BUTTON_2_PIN), isr_control_inputs, CHANGE);
#endif
#ifdef MACRO_BUTTON_3_PIN
grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "Macro Pin 3");
pinMode(MACRO_BUTTON_3_PIN, INPUT_PULLUP);
initPin(MACRO_BUTTON_3_PIN, INPUT_PULLUP, "Macro Pin 3");
attachInterrupt(digitalPinToInterrupt(MACRO_BUTTON_3_PIN), isr_control_inputs, CHANGE);
#endif
#ifdef ENABLE_CONTROL_SW_DEBOUNCE
Expand Down
8 changes: 4 additions & 4 deletions Grbl_Esp32/src/UserOutput.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -33,14 +33,13 @@ namespace UserOutput {
}

void DigitalOutput::init() {
pinMode(_pin, OUTPUT);
initPin(_pin, OUTPUT, "User Digital Output", _number);
digitalWrite(_pin, LOW);

config_message();
}

void DigitalOutput::config_message() {
grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "User Digital Output:%d on Pin:%s", _number, pinName(_pin).c_str());
}

bool DigitalOutput::set_level(bool isOn) {
Expand All @@ -61,8 +60,9 @@ namespace UserOutput {
_pin = pin;
_pwm_frequency = pwm_frequency;

if (pin == UNDEFINED_PIN)
if (pin == UNDEFINED_PIN) {
return;
}

// determine the highest bit precision allowed by frequency
_resolution_bits = sys_calc_pwm_precision(_pwm_frequency);
Expand Down Expand Up @@ -113,4 +113,4 @@ namespace UserOutput {

return true;
}
}
}