mirror of
https://github.com/bdring/Grbl_Esp32.git
synced 2025-08-14 02:24:05 +02:00
Devt (#628)
* Fixed various small bugs (#605) * Fixed various small bugs * Fixed potential cast bug * Fixed double reporting of errors Co-authored-by: Stefan de Bruijn <stefan@nubilosoft.com> * Stallguard tuning (#607) * Devt (#571) * Handles Tranimic drivers errors better - If an unsupported driver is specified, it will give a message and not crash. * Cleaned up unused files Got rid of old unipolar files Got rid of servo axis feature - it is a motor class now Got rid of solenoid pen feature - never really used and it should be a motor class if it is. * Fix ENABLE_AUTHENTICATION (#569) * Fixed authentication code. * Removed another const cast Co-authored-by: Stefan de Bruijn <stefan@nubilosoft.com> * Fix step leakage with inverted steps (#570) * Fix step leakage with inverted steps * Update build date for merge Co-authored-by: Bart Dring <bdring@buildlog.net> Co-authored-by: Stefan de Bruijn <atlaste@users.noreply.github.com> Co-authored-by: Stefan de Bruijn <stefan@nubilosoft.com> Co-authored-by: Mitch Bradley <wmb@firmworks.com> Co-authored-by: Bart Dring <bdring@buildlog.net> * Update platformio.ini Per PR 583 * Created an enum for mode * Removing some unused machine defs * Added test machine definition * Clean up for PR * Remove test machine def. Co-authored-by: Stefan de Bruijn <atlaste@users.noreply.github.com> Co-authored-by: Stefan de Bruijn <stefan@nubilosoft.com> Co-authored-by: Mitch Bradley <wmb@firmworks.com> Co-authored-by: Bart Dring <bdring@buildlog.net> * Basic testing Complete * Made state variable volatile. * Homing cycle settings (#613) * Initial Tests Complete * Update Grbl.h * Update variables Co-authored-by: Mitch Bradley <wmb@firmworks.com> * fixed dual switches when inverted (#614) * fixed dual switches when inverted * Removed debug message * Cleaning up the machine defs Removed unused #defines. * Store coordinate offsets in NVS (#611) * Store coordinate offsets in NVS * Handle both old Eeprom formats * Implementing fixes (#616) - Stop creating additional tasks when limit_init() gets called again from homing and resets - Explicitly delete an object that was causing a memory loss. * Update Grbl.h * Tweak memory fix and add $H check for $Homing/Cycles * Fix G28.1 and G30.1 * Update Grbl.h * Homing cycle defaults (#624) * Changed to add homing cycle defaults There needs to be a way to set the homing cycle defaults in a machine definition. There will likely be a better way to do this in the future. * Update 10vSpindle.cpp Had wrong error message * Fixed typos and removed obsolete #defines * Probe cleanup (#625) * Cleanup probing code * Update Grbl.h * Update after review * Update error_codes_en_US.csv Co-authored-by: Stefan de Bruijn <atlaste@users.noreply.github.com> Co-authored-by: Stefan de Bruijn <stefan@nubilosoft.com> Co-authored-by: Mitch Bradley <wmb@firmworks.com> Co-authored-by: Bart Dring <bdring@buildlog.net>
This commit is contained in:
@@ -118,6 +118,30 @@
|
||||
# define DEFAULT_HOMING_SQUARED_AXES 0
|
||||
#endif
|
||||
|
||||
#ifndef DEFAULT_HOMING_CYCLE_0
|
||||
# define DEFAULT_HOMING_CYCLE_0 bit(Z_AXIS)
|
||||
#endif
|
||||
|
||||
#ifndef DEFAULT_HOMING_CYCLE_1
|
||||
# define DEFAULT_HOMING_CYCLE_1 (bit(X_AXIS) | bit(Y_AXIS))
|
||||
#endif
|
||||
|
||||
#ifndef DEFAULT_HOMING_CYCLE_2
|
||||
# define DEFAULT_HOMING_CYCLE_2 0
|
||||
#endif
|
||||
|
||||
#ifndef DEFAULT_HOMING_CYCLE_3
|
||||
# define DEFAULT_HOMING_CYCLE_3 0
|
||||
#endif
|
||||
|
||||
#ifndef DEFAULT_HOMING_CYCLE_4
|
||||
# define DEFAULT_HOMING_CYCLE_4 0
|
||||
#endif
|
||||
|
||||
#ifndef DEFAULT_HOMING_CYCLE_5
|
||||
# define DEFAULT_HOMING_CYCLE_5 0
|
||||
#endif
|
||||
|
||||
// ======== SPINDLE STUFF ====================
|
||||
#ifndef SPINDLE_TYPE
|
||||
# define SPINDLE_TYPE SpindleType::NONE
|
||||
@@ -575,6 +599,10 @@
|
||||
# define USER_ANALOG_PIN_3 UNDEFINED_PIN
|
||||
#endif
|
||||
|
||||
#ifndef PROBE_PIN
|
||||
# define PROBE_PIN UNDEFINED_PIN
|
||||
#endif
|
||||
|
||||
#ifndef USER_ANALOG_PIN_0_FREQ
|
||||
# define USER_ANALOG_PIN_0_FREQ 5000
|
||||
#endif
|
||||
|
@@ -271,10 +271,11 @@ Error gc_execute_line(char* line, uint8_t client) {
|
||||
mg_word_bit = ModalGroup::MG1;
|
||||
break;
|
||||
case 38: // G38 - probe
|
||||
#ifndef PROBE_PIN //only allow G38 "Probe" commands if a probe pin is defined.
|
||||
grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "No probe pin defined");
|
||||
FAIL(Error::GcodeUnsupportedCommand); // [Unsupported G command]
|
||||
#endif
|
||||
//only allow G38 "Probe" commands if a probe pin is defined.
|
||||
if (PROBE_PIN == UNDEFINED_PIN) {
|
||||
grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "No probe pin defined");
|
||||
FAIL(Error::GcodeUnsupportedCommand); // [Unsupported G command]
|
||||
}
|
||||
// Check for G0/1/2/3/38 being called with G10/28/30/92 on same block.
|
||||
// * G43.1 is also an axis command but is not explicitly defined this way.
|
||||
if (axis_command != AxisCommand::None) {
|
||||
|
@@ -23,7 +23,7 @@
|
||||
// Grbl versioning system
|
||||
|
||||
const char* const GRBL_VERSION = "1.3a";
|
||||
const char* const GRBL_VERSION_BUILD = "20200929";
|
||||
const char* const GRBL_VERSION_BUILD = "20201004";
|
||||
|
||||
//#include <sdkconfig.h>
|
||||
#include <Arduino.h>
|
||||
|
@@ -47,29 +47,27 @@
|
||||
|
||||
#define STEPPER_RESET GPIO_NUM_19
|
||||
|
||||
// Mosor Socket #1
|
||||
// Motor Socket #1
|
||||
#define X_DISABLE_PIN I2SO(0)
|
||||
#define X_DIRECTION_PIN I2SO(1)
|
||||
#define X_STEP_PIN I2SO(2)
|
||||
#define X_AXIS_SQUARING
|
||||
|
||||
// Mosor Socket #2
|
||||
// Motor Socket #2
|
||||
#define Y_DIRECTION_PIN I2SO(4)
|
||||
#define Y_STEP_PIN I2SO(5)
|
||||
#define Y_DISABLE_PIN I2SO(7)
|
||||
#define Y_AXIS_SQUARING
|
||||
|
||||
// Mosor Socket #3
|
||||
// Motor Socket #3
|
||||
#define Y2_DISABLE_PIN I2SO(8)
|
||||
#define Y2_DIRECTION_PIN I2SO(9)
|
||||
#define Y2_STEP_PIN I2SO(10)
|
||||
|
||||
// Mosor Socket #4
|
||||
// Motor Socket #4
|
||||
#define Z_DIRECTION_PIN I2SO(12)
|
||||
#define Z_STEP_PIN I2SO(13)
|
||||
#define Z_DISABLE_PIN I2SO(15)
|
||||
|
||||
// Mosor Socket #5
|
||||
// Motor Socket #5
|
||||
#define Z2_DISABLE_PIN I2SO(16)
|
||||
#define Z2_DIRECTION_PIN I2SO(17)
|
||||
#define Z2_STEP_PIN I2SO(18)
|
||||
|
@@ -47,29 +47,27 @@
|
||||
|
||||
#define STEPPER_RESET GPIO_NUM_19
|
||||
|
||||
// Mosor Socket #1
|
||||
// Motor Socket #1
|
||||
#define X_DISABLE_PIN I2SO(0)
|
||||
#define X_DIRECTION_PIN I2SO(1)
|
||||
#define X_STEP_PIN I2SO(2)
|
||||
#define X_AXIS_SQUARING
|
||||
|
||||
// Mosor Socket #2
|
||||
// Motor Socket #2
|
||||
#define Y_DIRECTION_PIN I2SO(4)
|
||||
#define Y_STEP_PIN I2SO(5)
|
||||
#define Y_DISABLE_PIN I2SO(7)
|
||||
#define Y_AXIS_SQUARING
|
||||
|
||||
// Mosor Socket #3
|
||||
// Motor Socket #3
|
||||
#define Z_DISABLE_PIN I2SO(8)
|
||||
#define Z_DIRECTION_PIN I2SO(9)
|
||||
#define Z_STEP_PIN I2SO(10)
|
||||
|
||||
// Mosor Socket #4
|
||||
// Motor Socket #4
|
||||
#define X2_DIRECTION_PIN I2SO(12)
|
||||
#define X2_STEP_PIN I2SO(13)
|
||||
#define X2_DISABLE_PIN I2SO(15)
|
||||
|
||||
// Mosor Socket #5
|
||||
// Motor Socket #5
|
||||
#define Y2_DISABLE_PIN I2SO(16)
|
||||
#define Y2_DIRECTION_PIN I2SO(17)
|
||||
#define Y2_STEP_PIN I2SO(18)
|
||||
|
@@ -26,16 +26,6 @@
|
||||
|
||||
#define N_AXIS 3
|
||||
|
||||
#ifdef HOMING_CYCLE_0
|
||||
#undef HOMING_CYCLE_0
|
||||
#endif
|
||||
#define HOMING_CYCLE_0 bit(Z_AXIS) // Z first
|
||||
|
||||
#ifdef HOMING_CYCLE_1
|
||||
#undef HOMING_CYCLE_1
|
||||
#endif
|
||||
#define HOMING_CYCLE_1 (bit(X_AXIS)|bit(Y_AXIS))
|
||||
|
||||
// === Special Features
|
||||
|
||||
// I2S (steppers & other output-only pins)
|
||||
@@ -110,27 +100,27 @@ Socket #5
|
||||
|
||||
*/
|
||||
|
||||
/*
|
||||
|
||||
// 4x Input Module in Socket #1
|
||||
// https://github.com/bdring/6-Pack_CNC_Controller/wiki/4x-Switch-Input-module
|
||||
#define X_LIMIT_PIN GPIO_NUM_33
|
||||
#define Y_LIMIT_PIN GPIO_NUM_32
|
||||
#define Z_LIMIT_PIN GPIO_NUM_35
|
||||
*/
|
||||
|
||||
// 4x Input Module in Socket #2
|
||||
// https://github.com/bdring/6-Pack_CNC_Controller/wiki/4x-Switch-Input-module
|
||||
#define X_LIMIT_PIN GPIO_NUM_2
|
||||
#define Y_LIMIT_PIN GPIO_NUM_25
|
||||
#define Z_LIMIT_PIN GPIO_NUM_39
|
||||
|
||||
// 4x Input Module in Socket #3
|
||||
// https://github.com/bdring/6-Pack_CNC_Controller/wiki/4x-Switch-Input-module
|
||||
#define CONTROL_CYCLE_START_PIN GPIO_NUM_26
|
||||
#define CONTROL_FEED_HOLD_PIN GPIO_NUM_4
|
||||
#define CONTROL_RESET_PIN GPIO_NUM_16
|
||||
#define CONTROL_SAFETY_DOOR_PIN GPIO_NUM_27
|
||||
//#define INVERT_CONTROL_PIN_MASK B0000
|
||||
// // 4x Input Module in Socket #2
|
||||
// // https://github.com/bdring/6-Pack_CNC_Controller/wiki/4x-Switch-Input-module
|
||||
// #define X_LIMIT_PIN GPIO_NUM_2
|
||||
// #define Y_LIMIT_PIN GPIO_NUM_25
|
||||
// #define Z_LIMIT_PIN GPIO_NUM_39
|
||||
|
||||
// // 4x Input Module in Socket #3
|
||||
// // https://github.com/bdring/6-Pack_CNC_Controller/wiki/4x-Switch-Input-module
|
||||
// #define CONTROL_CYCLE_START_PIN GPIO_NUM_26
|
||||
// #define CONTROL_FEED_HOLD_PIN GPIO_NUM_4
|
||||
// #define CONTROL_RESET_PIN GPIO_NUM_16
|
||||
// #define CONTROL_SAFETY_DOOR_PIN GPIO_NUM_27
|
||||
// //#define INVERT_CONTROL_PIN_MASK B0000
|
||||
|
||||
|
||||
// ================= Setting Defaults ==========================
|
||||
|
@@ -54,6 +54,9 @@
|
||||
#define SPINDLE_TYPE SpindleType::NONE
|
||||
|
||||
// defaults
|
||||
#define DEFAULT_HOMING_CYCLE_0 bit(Y_AXIS)
|
||||
#define DEFAULT_HOMING_CYCLE_1 bit(X_AXIS)
|
||||
|
||||
#define DEFAULT_STEP_PULSE_MICROSECONDS 3
|
||||
#define DEFAULT_STEPPER_IDLE_LOCK_TIME 255 // stay on
|
||||
|
||||
|
@@ -37,6 +37,15 @@
|
||||
|
||||
#define MACHINE_NAME "Test Drive - Demo Only No I/O!"
|
||||
|
||||
// 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
|
||||
|
||||
#define SPINDLE_TYPE SpindleType::NONE
|
||||
|
||||
#ifdef USE_RMT_STEPS
|
||||
|
@@ -375,14 +375,13 @@ GCUpdatePos mc_probe_cycle(float* target, plan_line_data_t* pl_data, uint8_t par
|
||||
uint8_t is_probe_away = bit_istrue(parser_flags, GCParserProbeIsAway);
|
||||
uint8_t is_no_error = bit_istrue(parser_flags, GCParserProbeIsNoError);
|
||||
sys.probe_succeeded = false; // Re-initialize probe history before beginning cycle.
|
||||
probe_configure_invert_mask(is_probe_away);
|
||||
set_probe_direction(is_probe_away);
|
||||
// After syncing, check if probe is already triggered. If so, halt and issue alarm.
|
||||
// NOTE: This probe initialization error applies to all probing cycles.
|
||||
if (probe_get_state()) { // Check probe pin state.
|
||||
if (probe_get_state() ^ is_probe_away) { // Check probe pin state.
|
||||
system_set_exec_alarm(ExecAlarm::ProbeFailInitial);
|
||||
protocol_execute_realtime();
|
||||
probe_configure_invert_mask(false); // Re-initialize invert mask before returning.
|
||||
return GCUpdatePos::None; // Nothing else to do but bail.
|
||||
return GCUpdatePos::None; // Nothing else to do but bail.
|
||||
}
|
||||
// Setup and queue probing motion. Auto cycle-start should not start the cycle.
|
||||
mc_line(target, pl_data);
|
||||
@@ -407,9 +406,8 @@ GCUpdatePos mc_probe_cycle(float* target, plan_line_data_t* pl_data, uint8_t par
|
||||
} else {
|
||||
sys.probe_succeeded = true; // Indicate to system the probing cycle completed successfully.
|
||||
}
|
||||
sys_probe_state = PROBE_OFF; // Ensure probe state monitor is disabled.
|
||||
probe_configure_invert_mask(false); // Re-initialize invert mask.
|
||||
protocol_execute_realtime(); // Check and execute run-time commands
|
||||
sys_probe_state = PROBE_OFF; // Ensure probe state monitor is disabled.
|
||||
protocol_execute_realtime(); // Check and execute run-time commands
|
||||
// Reset the stepper and planner buffers to remove the remainder of the probe motion.
|
||||
st_reset(); // Reset step segment buffer.
|
||||
plan_reset(); // Reset planner buffer. Zero planner positions. Ensure probing motion is cleared.
|
||||
|
@@ -24,47 +24,40 @@
|
||||
#include "Grbl.h"
|
||||
|
||||
// Inverts the probe pin state depending on user settings and probing cycle mode.
|
||||
uint8_t probe_invert_mask;
|
||||
static bool is_probe_away;
|
||||
|
||||
// Probe pin initialization routine.
|
||||
void probe_init() {
|
||||
#ifdef PROBE_PIN
|
||||
# ifdef DISABLE_PROBE_PIN_PULL_UP
|
||||
pinMode(PROBE_PIN, INPUT);
|
||||
# else
|
||||
pinMode(PROBE_PIN, INPUT_PULLUP); // Enable internal pull-up resistors. Normal high operation.
|
||||
# endif
|
||||
probe_configure_invert_mask(false); // Initialize invert mask.
|
||||
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);
|
||||
#else
|
||||
pinMode(PROBE_PIN, INPUT_PULLUP); // 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;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
// Called by probe_init() and the mc_probe() routines. Sets up the probe pin invert mask to
|
||||
// appropriately set the pin logic according to setting for normal-high/normal-low operation
|
||||
// and the probing cycle modes for toward-workpiece/away-from-workpiece.
|
||||
void probe_configure_invert_mask(uint8_t is_probe_away) {
|
||||
probe_invert_mask = 0; // Initialize as zero.
|
||||
if (probe_invert->get()) {
|
||||
probe_invert_mask ^= PROBE_MASK;
|
||||
}
|
||||
if (is_probe_away) {
|
||||
probe_invert_mask ^= PROBE_MASK;
|
||||
}
|
||||
void set_probe_direction(bool is_away) {
|
||||
is_probe_away = is_away;
|
||||
}
|
||||
|
||||
// Returns the probe pin state. Triggered = true. Called by gcode parser and probe state monitor.
|
||||
uint8_t probe_get_state() {
|
||||
#ifdef PROBE_PIN
|
||||
return digitalRead(PROBE_PIN) ^ probe_invert_mask;
|
||||
#else
|
||||
return false;
|
||||
#endif
|
||||
bool probe_get_state() {
|
||||
return digitalRead(PROBE_PIN) ^ probe_invert->get();
|
||||
}
|
||||
|
||||
// Monitors probe pin state and records the system position when detected. Called by the
|
||||
// stepper ISR per ISR tick.
|
||||
// NOTE: This function must be extremely efficient as to not bog down the stepper ISR.
|
||||
void probe_state_monitor() {
|
||||
if (probe_get_state()) {
|
||||
if (probe_get_state() ^ is_probe_away) {
|
||||
sys_probe_state = PROBE_OFF;
|
||||
memcpy(sys_probe_position, sys_position, sizeof(sys_position));
|
||||
bit_true(sys_rt_exec_state, EXEC_MOTION_CANCEL);
|
||||
|
@@ -30,13 +30,11 @@ const int PROBE_ACTIVE = 1; // Actively watching the input pin.
|
||||
// Probe pin initialization routine.
|
||||
void probe_init();
|
||||
|
||||
// Called by probe_init() and the mc_probe() routines. Sets up the probe pin invert mask to
|
||||
// appropriately set the pin logic according to setting for normal-high/normal-low operation
|
||||
// and the probing cycle modes for toward-workpiece/away-from-workpiece.
|
||||
void probe_configure_invert_mask(uint8_t is_probe_away);
|
||||
// setup probing direction G38.2 vs. G38.4
|
||||
void set_probe_direction(bool is_away);
|
||||
|
||||
// Returns probe pin state. Triggered = true. Called by gcode parser and probe state monitor.
|
||||
uint8_t probe_get_state();
|
||||
bool probe_get_state();
|
||||
|
||||
// Monitors probe pin state and records the system position when detected. Called by the
|
||||
// stepper ISR per ISR tick.
|
||||
|
@@ -537,6 +537,10 @@ void FlagSetting::setDefault() {
|
||||
|
||||
Error FlagSetting::setStringValue(char* s) {
|
||||
s = trim(s);
|
||||
Error err = check(s);
|
||||
if (err != Error::Ok) {
|
||||
return err;
|
||||
}
|
||||
_currentValue = (strcasecmp(s, "on") == 0) || (strcasecmp(s, "true") == 0) || (strcasecmp(s, "enabled") == 0) ||
|
||||
(strcasecmp(s, "yes") == 0) || (strcasecmp(s, "1") == 0);
|
||||
// _storedValue is -1, 0, or 1
|
||||
|
@@ -375,9 +375,10 @@ void make_settings() {
|
||||
spindle_type = new EnumSetting(NULL, EXTENDED, WG, NULL, "Spindle/Type", static_cast<int8_t>(SPINDLE_TYPE), &spindleTypes);
|
||||
stallguard_debug_mask = new AxisMaskSetting(EXTENDED, WG, NULL, "Report/StallGuard", 0, checkStallguardDebugMask);
|
||||
|
||||
const char* homing_names[] = { "Homing/Cycle0", "Homing/Cycle1", "Homing/Cycle2",
|
||||
"Homing/Cycle3", "Homing/Cycle4", "Homing/Cycle5" };
|
||||
for (uint8_t i = 0; i < MAX_N_AXIS; i++) {
|
||||
homing_cycle[i] = new AxisMaskSetting(EXTENDED, WG, NULL, homing_names[i], 0);
|
||||
}
|
||||
homing_cycle[0] = new AxisMaskSetting(EXTENDED, WG, NULL, "Homing/Cycle0", DEFAULT_HOMING_CYCLE_0);
|
||||
homing_cycle[1] = new AxisMaskSetting(EXTENDED, WG, NULL, "Homing/Cycle1", DEFAULT_HOMING_CYCLE_1);
|
||||
homing_cycle[2] = new AxisMaskSetting(EXTENDED, WG, NULL, "Homing/Cycle2", DEFAULT_HOMING_CYCLE_2);
|
||||
homing_cycle[3] = new AxisMaskSetting(EXTENDED, WG, NULL, "Homing/Cycle3", DEFAULT_HOMING_CYCLE_3);
|
||||
homing_cycle[4] = new AxisMaskSetting(EXTENDED, WG, NULL, "Homing/Cycle4", DEFAULT_HOMING_CYCLE_4);
|
||||
homing_cycle[5] = new AxisMaskSetting(EXTENDED, WG, NULL, "Homing/Cycle5", DEFAULT_HOMING_CYCLE_5);
|
||||
}
|
||||
|
@@ -44,7 +44,7 @@ namespace Spindles {
|
||||
#endif
|
||||
|
||||
if (_output_pin == UNDEFINED_PIN) {
|
||||
grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "Warning: BESC output pin not defined");
|
||||
grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "Warning: Spindle output pin not defined");
|
||||
return; // We cannot continue without the output pin
|
||||
}
|
||||
|
||||
|
@@ -16,6 +16,7 @@
|
||||
"15","Travel exceeded","Jog target exceeds machine travel. Jog command has been ignored."
|
||||
"16","Invalid jog command","Jog command has no '=' or contains prohibited g-code."
|
||||
"17","Setting disabled","Laser mode requires PWM output."
|
||||
"18","No Homing/Cycle defined in settings","Set some $homing/CycleX= Settings"
|
||||
"20","Unsupported command","Unsupported or invalid g-code command found in block."
|
||||
"21","Modal group violation","More than one g-code command from same modal group found in block."
|
||||
"22","Undefined feed rate","Feed rate has not yet been set or is undefined."
|
||||
|
|
Reference in New Issue
Block a user