Skip to content

Commit

Permalink
Merge pull request #88 from bdring/Devt
Browse files Browse the repository at this point in the history
Devt
  • Loading branch information
bdring authored Oct 28, 2021
2 parents c09b1a4 + cd96a1d commit e1ec0bc
Show file tree
Hide file tree
Showing 18 changed files with 60 additions and 46 deletions.
Binary file modified FluidNC/data/index.html.gz
Binary file not shown.
2 changes: 1 addition & 1 deletion FluidNC/src/Machine/Axis.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -71,7 +71,7 @@ namespace Machine {
}

// Does this axis have 2 motors?
bool Axis::hasDualMotor() { return _motors[0] && _motors[1]; }
bool Axis::hasDualMotor() { return _motors[0] && _motors[0]->isReal() && _motors[1] && _motors[1]->isReal(); }

// How many motors have switches defined?
int Axis::motorsWithSwitches() {
Expand Down
1 change: 1 addition & 0 deletions FluidNC/src/Machine/Homing.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -180,6 +180,7 @@ namespace Machine {
// Normal termination for pulloff cycle
remainingMotors = 0;
}
pollClients();
} while (remainingMotors);

Stepper::reset(); // Immediately force kill steppers and reset step segment buffer.
Expand Down
22 changes: 5 additions & 17 deletions FluidNC/src/Machine/MachineConfig.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -31,6 +31,7 @@ namespace Machine {
void MachineConfig::group(Configuration::HandlerBase& handler) {
handler.item("board", _board);
handler.item("name", _name);
handler.item("meta", _meta);

handler.section("stepping", _stepping);
handler.section("axes", _axes);
Expand Down Expand Up @@ -62,12 +63,10 @@ namespace Machine {
}

if (_coolant == nullptr) {
log_info("Coolant: using defaults");
_coolant = new CoolantControl();
}

if (_probe == nullptr) {
log_info("Probe: using defaults");
_probe = new Probe();
}

Expand All @@ -91,7 +90,6 @@ namespace Machine {
// Only if an i2so section is present will config->_i2so be non-null

if (_control == nullptr) {
log_info("Control: using defaults");
_control = new Control();
}

Expand All @@ -100,7 +98,6 @@ namespace Machine {
}

if (_spindles.size() == 0) {
log_info("Spindle: using defaults (no spindle)");
_spindles.push_back(new Spindles::Null());
}

Expand Down Expand Up @@ -147,7 +144,6 @@ namespace Machine {
log_info("config file " << path << " is empty");
return 0;
}
// log_debug("Configuration file has " << int(filesize) << " bytes");
buffer = new char[filesize + 1];

size_t pos = 0;
Expand All @@ -162,8 +158,6 @@ namespace Machine {
file.close();
buffer[filesize] = 0;

// log_debug("Read config file:\n" << buffer);

if (pos != filesize) {
delete[] buffer;

Expand All @@ -176,8 +170,6 @@ namespace Machine {
char defaultConfig[] = "name: Default (Test Drive)\nboard: None\n";

bool MachineConfig::load(const char* filename) {
// log_info("Heap size before load config is " << uint32_t(xPortGetFreeHeapSize()));

// If the system crashes we skip the config file and use the default
// builtin config. This helps prevent reset loops on bad config files.
size_t filesize = 0;
Expand All @@ -193,7 +185,7 @@ namespace Machine {

if (filesize > 0) {
input = new StringRange(buffer, buffer + filesize);
log_info("Configuration file: " << filename);
log_info("Configuration file:" << filename);

} else {
log_info("Using default configuration");
Expand All @@ -202,8 +194,6 @@ namespace Machine {
// Process file:
bool successful = false;
try {
// log_info("Heap size before parsing is " << uint32_t(xPortGetFreeHeapSize()));

Configuration::Parser parser(input->begin(), input->end());
Configuration::ParserHandler handler(parser);

Expand All @@ -222,8 +212,6 @@ namespace Machine {

log_debug("Running after-parse tasks");

// log_info("Heap size before after-parse is " << uint32_t(xPortGetFreeHeapSize()));

try {
Configuration::AfterParse afterParse;
config->afterParse();
Expand All @@ -232,8 +220,6 @@ namespace Machine {

log_debug("Checking configuration");

// log_info("Heap size before validation is " << uint32_t(xPortGetFreeHeapSize()));

try {
Configuration::Validator validator;
config->validate();
Expand All @@ -244,7 +230,9 @@ namespace Machine {

successful = (sys.state != State::ConfigAlarm);

log_info("Configuration is " << (successful ? "valid" : "invalid"));
if (!successful) {
log_info("Configuration is invalid");
}

} catch (const Configuration::ParseException& ex) {
sys.state = State::ConfigAlarm;
Expand Down
2 changes: 1 addition & 1 deletion FluidNC/src/Machine/MachineConfig.h
Original file line number Diff line number Diff line change
Expand Up @@ -82,7 +82,7 @@ namespace Machine {

String _board = "None";
String _name = "None";

String _meta = "";
#if 1
static MachineConfig*& instance() {
static MachineConfig* instance = nullptr;
Expand Down
2 changes: 2 additions & 0 deletions FluidNC/src/Machine/Motor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -55,5 +55,7 @@ namespace Machine {
_allLimitPin->makeDualMask();
}

bool Motor::isReal() { return _driver->isReal(); }

Motor::~Motor() { delete _driver; }
}
1 change: 1 addition & 0 deletions FluidNC/src/Machine/Motor.h
Original file line number Diff line number Diff line change
Expand Up @@ -39,6 +39,7 @@ namespace Machine {
void group(Configuration::HandlerBase& handler) override;
void afterParse() override;
bool hasSwitches();
bool isReal();
void makeDualSwitches();
void init();
void config_motor();
Expand Down
3 changes: 3 additions & 0 deletions FluidNC/src/Motors/MotorDriver.h
Original file line number Diff line number Diff line change
Expand Up @@ -95,6 +95,9 @@ namespace MotorDrivers {
// Name is required for the configuration factory to work.
virtual const char* name() const = 0;

// Test for a real motor as opposed to a NullMotor placeholder
virtual bool isReal() { return true; }

// Virtual base classes require a virtual destructor.
virtual ~MotorDriver() {}

Expand Down
2 changes: 2 additions & 0 deletions FluidNC/src/Motors/NullMotor.h
Original file line number Diff line number Diff line change
Expand Up @@ -9,6 +9,8 @@ namespace MotorDrivers {

bool set_homing_mode(bool isHoming) { return false; }

bool isReal() override { return false; }

// Configuration handlers:
void group(Configuration::HandlerBase& handler) override {}

Expand Down
2 changes: 1 addition & 1 deletion FluidNC/src/Pin.h
Original file line number Diff line number Diff line change
Expand Up @@ -103,7 +103,7 @@ class Pin {
// External libraries normally use digitalWrite, digitalRead and setMode. Since we cannot handle that behavior, we
// just give back the pinnum_t for getNative.
inline pinnum_t getNative(Capabilities expectedBehavior) const {
Assert(_detail->capabilities().has(expectedBehavior), "Requested pin does not have the expected behavior.");
Assert(_detail->capabilities().has(expectedBehavior), "Requested pin %s does not have the expected behavior.",name().c_str());
return _detail->_index;
}

Expand Down
36 changes: 19 additions & 17 deletions FluidNC/src/ProcessSettings.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -274,34 +274,36 @@ static Error home_b(const char* value, WebUI::AuthenticationLevel auth_level, Pr
static Error home_c(const char* value, WebUI::AuthenticationLevel auth_level, Print& out) {
return home(bitnum_to_mask(C_AXIS));
}
static void write_limit_set(uint32_t mask) {
static void write_limit_set(uint32_t mask, Print& out) {
const char* motor0AxisName = "xyzabc";
for (int i = 0; i < MAX_N_AXIS; i++) {
Uart0.write(bitnum_is_true(mask, i) ? char(motor0AxisName[i]) : ' ');
out.write(bitnum_is_true(mask, i) ? char(motor0AxisName[i]) : ' ');
}
const char* motor1AxisName = "XYZABC";
for (int i = 0; i < MAX_N_AXIS; i++) {
Uart0.write(bitnum_is_true(mask, i + 16) ? char(motor1AxisName[i]) : ' ');
out.write(bitnum_is_true(mask, i + 16) ? char(motor1AxisName[i]) : ' ');
}
}
static Error show_limits(const char* value, WebUI::AuthenticationLevel auth_level, Print& out) {
Uart0.print("Send ! to exit\n");
Uart0.print("Homing Axes: ");
write_limit_set(Machine::Axes::homingMask);
Uart0.write('\n');
Uart0.print("Limit Axes: ");
write_limit_set(Machine::Axes::limitMask);
Uart0.write('\n');
Uart0.print("PosLimitPins NegLimitPins\n");
out.print("Send ! to exit\n");
out.print("Homing Axes: ");
write_limit_set(Machine::Axes::homingMask, out);
out.write('\n');
out.print("Limit Axes: ");
write_limit_set(Machine::Axes::limitMask, out);
out.write('\n');
out.print(" PosLimitPins NegLimitPins\n");
do {
write_limit_set(Machine::Axes::posLimitMask);
Uart0.write(' ');
write_limit_set(Machine::Axes::negLimitMask);
Uart0.write('\n');
vTaskDelay(500);
out.write(": "); // Prevents WebUI from suppressing an empty line
write_limit_set(Machine::Axes::posLimitMask, out);
out.write(' ');
write_limit_set(Machine::Axes::negLimitMask, out);
out.print("\r\n");
vTaskDelay(500); // Delay for a reasonable repeat rate
pollClients();
} while (!rtFeedHold);
rtFeedHold = false;
Uart0.write('\n');
out.write('\n');
return Error::Ok;
}
static Error go_to_sleep(const char* value, WebUI::AuthenticationLevel auth_level, Print& out) {
Expand Down
13 changes: 11 additions & 2 deletions FluidNC/src/Protocol.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -252,12 +252,12 @@ static void protocol_do_alarm() {
report_feedback_message(Message::CriticalEvent);
rtReset = false; // Disable any existing reset
do {
// Block everything, except reset and status reports, until user issues reset or power
// Block everything except reset and status reports until user issues reset or power
// cycles. Hard limits typically occur while unattended or not paying attention. Gives
// the user and a GUI time to do what is needed before resetting, like killing the
// incoming stream. The same could be said about soft limits. While the position is not
// lost, continued streaming could cause a serious crash if by chance it gets executed.
vTaskDelay(1); // give serial task some time
pollClients(); // Handle ^X realtime RESET command
} while (!rtReset);
break;
default:
Expand Down Expand Up @@ -445,6 +445,11 @@ static void protocol_do_sleep() {
sys.state = State::Sleep;
}

void protocol_cancel_disable_steppers() {
// Cancel any pending stepper disable.
idleEndTime = 0;
}

static void protocol_do_initiate_cycle() {
// Start cycle only if queued motions exist in planner buffer and the motion is not canceled.
sys.step_control = {}; // Restore step control to normal operation
Expand All @@ -457,6 +462,9 @@ static void protocol_do_initiate_cycle() {
sys.suspend.value = 0; // Break suspend state.
sys.state = State::Idle;
}

// Make sure the steppers can't be scheduled for a shutdown while this cycle is running.
protocol_cancel_disable_steppers();
}

// The handlers for rtFeedHold, rtMotionCancel, and rtsDafetyDoor clear rtCycleStart to
Expand Down Expand Up @@ -952,6 +960,7 @@ static void protocol_exec_rt_suspend() {
}
}
}
pollClients(); // Handle realtime commands like status report, cycle start and reset
protocol_exec_rt_system();
}
}
2 changes: 1 addition & 1 deletion FluidNC/src/Report.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -661,7 +661,7 @@ void report_realtime_status(Print& client) {
client << "|SD:" << config->_sdCard->percent_complete() << "," << config->_sdCard->filename();
}
#ifdef DEBUG_STEPPER_ISR
client << "|ISRs:" << Stepper::isr_count;
client << "|ISRs:" << config->_stepping->isr_count;
#endif
#ifdef DEBUG_REPORT_HEAP
client << "|Heap:" << esp.getHeapSize();
Expand Down
6 changes: 3 additions & 3 deletions FluidNC/src/Serial.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -205,8 +205,9 @@ void client_init() {
register_client(&Uart0); // USB Serial
register_client(&WebUI::inputBuffer); // Macros
}

InputClient* pollClients() {
auto sdcard = config->_sdCard;

for (auto client : clientq) {
auto source = client->_in;
int c = source->read();
Expand Down Expand Up @@ -244,7 +245,7 @@ InputClient* pollClients() {
}
if (ch == '\n') {
client->_line_num++;
if (config->_sdCard->get_state() < SDCard::State::Busy) {
if (sdcard->get_state() < SDCard::State::Busy) {
client->_line[client->_linelen] = '\0';
client->_line_returned = true;
display("GCODE", client->_line);
Expand All @@ -267,7 +268,6 @@ InputClient* pollClients() {
WebUI::wifi_services.handle(); // OTA, web_server, telnet_server polling
#endif

auto sdcard = config->_sdCard;
// _readyNext indicates that input is coming from a file and
// the GCode system is ready for another line.
if (sdcard && sdcard->_readyNext) {
Expand Down
2 changes: 1 addition & 1 deletion FluidNC/src/Spindles/NullSpindle.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -27,7 +27,7 @@ namespace Spindles {
_current_state = state;
sys.spindle_speed = speed;
}
void Null::config_message() { log_info("No spindle"); }
void Null::config_message() { /*log_info("No spindle");*/ }

// Configuration registration
namespace {
Expand Down
4 changes: 2 additions & 2 deletions FluidNC/src/WebUI/JSONEncoder.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -6,7 +6,7 @@
namespace WebUI {
// Constructor. If _pretty is true, newlines are
// inserted into the JSON string for easy reading.
JSONencoder::JSONencoder(bool pretty, Print* s) : pretty(pretty), level(0), str(""), stream(s) { count[level] = 0; }
JSONencoder::JSONencoder(bool pretty, Print* s) : pretty(pretty), level(0), str(""), stream(s), category("nvs") { count[level] = 0; }

// Constructor. If _pretty is true, newlines are
// inserted into the JSON string for easy reading.
Expand Down Expand Up @@ -150,7 +150,7 @@ namespace WebUI {
// a value passed in as a C-style string.
void JSONencoder::begin_webui(const char* name, const char* help, const char* type, const char* val) {
begin_object();
member("F", "network");
member("F", category);
// P is the name that WebUI uses to set a new value.
// H is the legend that WebUI displays in the UI.
// The distinction used to be important because, prior to the introuction
Expand Down
4 changes: 4 additions & 0 deletions FluidNC/src/WebUI/JSONEncoder.h
Original file line number Diff line number Diff line change
Expand Up @@ -23,6 +23,8 @@ namespace WebUI {
void line();
Print* stream;

String category;

public:
// If you don't set _pretty it defaults to false
JSONencoder();
Expand All @@ -36,6 +38,8 @@ namespace WebUI {
// begin() starts the encoding process.
void begin();

void setCategory(const char* cat) { category = cat; }

// end() returns the encoded string
String end();

Expand Down
2 changes: 2 additions & 0 deletions FluidNC/src/WebUI/WebSettings.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -637,11 +637,13 @@ namespace WebUI {
j.begin_array("EEPROM");

// NVS settings
j.setCategory("nvs");
for (Setting* js = Setting::List; js; js = js->next()) {
js->addWebui(&j);
}

// Configuration tree
j.setCategory("tree");
Configuration::JsonGenerator gen(j);
config->group(gen);

Expand Down

0 comments on commit e1ec0bc

Please sign in to comment.