diff --git a/FluidNC/data/index.html.gz b/FluidNC/data/index.html.gz
index 05a4f23a1..5d5db5e3f 100644
Binary files a/FluidNC/data/index.html.gz and b/FluidNC/data/index.html.gz differ
diff --git a/FluidNC/src/Configuration/JsonGenerator.cpp b/FluidNC/src/Configuration/JsonGenerator.cpp
index 9c10c1431..5c794eddd 100644
--- a/FluidNC/src/Configuration/JsonGenerator.cpp
+++ b/FluidNC/src/Configuration/JsonGenerator.cpp
@@ -50,13 +50,13 @@ namespace Configuration {
void JsonGenerator::item(const char* name, bool& value) {
enter(name);
- const char* val = value ? "Yes" : "No";
+ const char* val = value ? "1" : "0";
_encoder.begin_webui(_currentPath, _currentPath, "B", val);
_encoder.begin_array("O");
{
_encoder.begin_object();
- _encoder.member("No", 0);
- _encoder.member("Yes", 1);
+ _encoder.member("False", 0);
+ _encoder.member("True", 1);
_encoder.end_object();
}
_encoder.end_array();
@@ -114,19 +114,21 @@ namespace Configuration {
void JsonGenerator::item(const char* name, int& value, EnumItem* e) {
enter(name);
- const char* str = "unknown";
- for (; e->name; ++e) {
- if (value == e->value) {
- str = e->name;
+ int selected_val = 0;
+ //const char* str = "unknown";
+ for (auto e2 = e; e2->name; ++e2) {
+ if (value == e2->value) {
+ //str = e2->name;
+ selected_val = e2->value;
break;
}
}
- _encoder.begin_webui(_currentPath, _currentPath, "B", str);
+ _encoder.begin_webui(_currentPath, _currentPath, "B", selected_val);
_encoder.begin_array("O");
- for (; e->name; ++e) {
+ for (auto e2 = e; e2->name; ++e2) {
_encoder.begin_object();
- _encoder.member(e->name, e->value);
+ _encoder.member(e2->name, e2->value);
_encoder.end_object();
}
_encoder.end_array();
diff --git a/FluidNC/src/Configuration/RuntimeSetting.cpp b/FluidNC/src/Configuration/RuntimeSetting.cpp
index af0fa69d4..c2b12c59a 100644
--- a/FluidNC/src/Configuration/RuntimeSetting.cpp
+++ b/FluidNC/src/Configuration/RuntimeSetting.cpp
@@ -12,7 +12,9 @@ namespace Configuration {
RuntimeSetting::RuntimeSetting(const char* key, const char* value, Print& out) : newValue_(value), out_(out) {
// Remove leading '/' if it is present
setting_ = (*key == '/') ? key + 1 : key;
- start_ = setting_;
+ // Also remove trailing '/' if it is present
+
+ start_ = setting_;
// Read fence for config. Shouldn't be necessary, but better safe than sorry.
std::atomic_thread_fence(std::memory_order::memory_order_seq_cst);
}
@@ -26,7 +28,7 @@ namespace Configuration {
for (; *next && *next != '/'; ++next) {}
// Do we have a child?
- if (*next == '/') {
+ if (*next == '/' && next[1] != '\0') {
++next;
start_ = next;
@@ -34,11 +36,9 @@ namespace Configuration {
value->group(*this);
} else {
if (newValue_ == nullptr) {
- allClients << dataBeginMarker;
- allClients << setting_ << ":\n";
+ allClients << "/" << setting_ << ":\n";
Configuration::Generator generator(allClients, 1);
value->group(generator);
- allClients << dataEndMarker;
isHandled_ = true;
} else {
log_error("Can't set a value on a section");
@@ -54,9 +54,10 @@ namespace Configuration {
if (is(name)) {
isHandled_ = true;
if (newValue_ == nullptr) {
- out_ << "$" << setting_ << "=" << (value ? "true" : "false") << '\n';
+ out_ << "$/" << setting_ << "=" << (value ? "true" : "false") << '\n';
} else {
- value = (!strcasecmp(newValue_, "true"));
+ value = (!strcasecmp(newValue_, "true") || !strcasecmp(newValue_, "yes") || !strcasecmp(newValue_, "1"));
+ log_info("Bool value:" << value);
}
}
}
@@ -65,7 +66,7 @@ namespace Configuration {
if (is(name)) {
isHandled_ = true;
if (newValue_ == nullptr) {
- out_ << "$" << setting_ << "=" << value << '\n';
+ out_ << "$/" << setting_ << "=" << value << '\n';
} else {
value = atoi(newValue_);
}
@@ -76,7 +77,7 @@ namespace Configuration {
if (is(name)) {
isHandled_ = true;
if (newValue_ == nullptr) {
- out_ << "$" << setting_ << "=" << value << '\n';
+ out_ << "$/" << setting_ << "=" << value << '\n';
} else {
char* floatEnd;
value = strtof(newValue_, &floatEnd);
@@ -88,7 +89,7 @@ namespace Configuration {
if (is(name)) {
isHandled_ = true;
if (newValue_ == nullptr) {
- out_ << "$" << setting_ << "=" << value << '\n';
+ out_ << "$/" << setting_ << "=" << value << '\n';
} else {
value = String(newValue_);
}
@@ -99,16 +100,28 @@ namespace Configuration {
if (is(name)) {
isHandled_ = true;
if (newValue_ == nullptr) {
- for (; e->name; ++e) {
- if (e->value == value) {
- out_ << "$" << setting_ << "=" << e->name << '\n';
+ for (auto e2 = e; e2->name; ++e2) {
+ if (e2->value == value) {
+ out_ << "$/" << setting_ << "=" << e2->name << '\n';
return;
}
}
+
} else {
- for (; e->name; ++e) {
- if (!strcasecmp(newValue_, e->name)) {
- value = e->value;
+ if (isdigit(newValue_[0])) { // if the first char is a number. assume it is an index of a webui enum list
+ int indexVal = 0;
+ indexVal = atoi(newValue_);
+ for (auto e2 = e; e2->name; ++e2) {
+ if (e2->value == indexVal) {
+ value = e2->value;
+ newValue_ = e2->name;
+ return;
+ }
+ }
+ }
+ for (auto e2 = e; e2->name; ++e2) {
+ if (!strcasecmp(newValue_, e2->name)) {
+ value = e2->value;
return;
}
}
@@ -169,7 +182,7 @@ namespace Configuration {
if (is(name)) {
isHandled_ = true;
if (newValue_ == nullptr) {
- out_ << "$" << setting_ << "=" << value.toString() << '\n';
+ out_ << "$/" << setting_ << "=" << value.toString() << '\n';
} else {
IPAddress ip;
if (!ip.fromString(newValue_)) {
@@ -184,7 +197,7 @@ namespace Configuration {
if (is(name)) {
isHandled_ = true;
if (newValue_ == nullptr) {
- out_ << "$" << setting_ << "=" << value.name() << '\n';
+ out_ << "$/" << setting_ << "=" << value.name() << '\n';
} else {
out_ << "Runtime setting of Pin objects is not supported\n";
// auto parsed = Pin::create(newValue);
diff --git a/FluidNC/src/FileStream.cpp b/FluidNC/src/FileStream.cpp
index 7b0bb2bcb..62244b632 100644
--- a/FluidNC/src/FileStream.cpp
+++ b/FluidNC/src/FileStream.cpp
@@ -28,33 +28,31 @@ size_t FileStream::write(const uint8_t* buffer, size_t length) {
}
FileStream::FileStream(const char* filename, const char* mode, const char* defaultFs) {
- String path;
-
if (!filename || !*filename) {
throw Error::FsFailedCreateFile;
}
// Insert the default file system prefix if a file system name is not present
if (*filename != '/') {
- path = "/";
- path += defaultFs;
- path += "/";
+ _path = "/";
+ _path += defaultFs;
+ _path += "/";
}
- path += filename;
+ _path += filename;
// Map /localfs/ to the actual name of the local file system
- if (path.startsWith("/localfs/")) {
- path.replace("/localfs/", "/spiffs/");
+ if (_path.startsWith("/localfs/")) {
+ _path.replace("/localfs/", "/spiffs/");
}
- if (path.startsWith("/sd/")) {
+ if (_path.startsWith("/sd/")) {
if (config->_sdCard->begin(SDCard::State::BusyWriting) != SDCard::State::Idle) {
throw Error::FsFailedMount;
}
_isSD = true;
}
- _fd = fopen(path.c_str(), mode);
+ _fd = fopen(_path.c_str(), mode);
if (!_fd) {
throw strcmp(mode, "w") ? Error::FsFailedOpenFile : Error::FsFailedCreateFile;
}
diff --git a/FluidNC/src/FileStream.h b/FluidNC/src/FileStream.h
index 75d44f70a..3f15b7c14 100644
--- a/FluidNC/src/FileStream.h
+++ b/FluidNC/src/FileStream.h
@@ -7,12 +7,18 @@ extern "C" {
}
class FileStream : public Stream {
- bool _isSD;
- FILE* _fd;
+ bool _isSD;
+ FILE* _fd;
+ String _path;
public:
FileStream(const char* filename, const char* mode, const char* defaultFs = "localfs");
+ String path() {
+ String retval = _path;
+ retval.replace("/spiffs/", "/localfs/");
+ return retval;
+ }
int available() override;
int read() override;
int peek() override;
diff --git a/FluidNC/src/Motors/TrinamicBase.cpp b/FluidNC/src/Motors/TrinamicBase.cpp
index d538ef62a..870c4d08e 100644
--- a/FluidNC/src/Motors/TrinamicBase.cpp
+++ b/FluidNC/src/Motors/TrinamicBase.cpp
@@ -59,7 +59,7 @@ namespace MotorDrivers {
bool TrinamicBase::report_open_load(bool ola, bool olb) {
if (ola || olb) {
- log_info(" Driver Open Load a:" << yn(ola) << " b:" << yn(olb));
+ log_warn(" Driver Open Load a:" << yn(ola) << " b:" << yn(olb));
return true;
}
return false; // no error
@@ -67,14 +67,14 @@ namespace MotorDrivers {
bool TrinamicBase::report_short_to_ground(bool s2ga, bool s2gb) {
if (s2ga || s2gb) {
- log_info(" Driver Short Coil a:" << yn(s2ga) << " b:" << yn(s2gb));
+ log_warn(" Driver Short Coil a:" << yn(s2ga) << " b:" << yn(s2gb));
}
return false; // no error
}
bool TrinamicBase::report_over_temp(bool ot, bool otpw) {
if (ot || otpw) {
- log_info(" Driver Temp Warning:" << yn(otpw) << " Fault:" << yn(ot));
+ log_warn(" Driver Temp Warning:" << yn(otpw) << " Fault:" << yn(ot));
return true;
}
return false; // no error
@@ -83,7 +83,7 @@ namespace MotorDrivers {
bool TrinamicBase::report_short_to_ps(bool vsa, bool vsb) {
// check for short to power supply
if (vsa || vsb) {
- log_info(" Driver Short vsa:" << yn(vsa) << " vsb:" << yn(vsb));
+ log_warn(" Driver Short vsa:" << yn(vsa) << " vsb:" << yn(vsb));
return true;
}
return false; // no error
diff --git a/FluidNC/src/Motors/TrinamicSpiDriver.cpp b/FluidNC/src/Motors/TrinamicSpiDriver.cpp
index da10369f2..81d9cde97 100644
--- a/FluidNC/src/Motors/TrinamicSpiDriver.cpp
+++ b/FluidNC/src/Motors/TrinamicSpiDriver.cpp
@@ -39,7 +39,7 @@ namespace MotorDrivers {
} else if (_driver_part_number == 5160) {
tmc5160 = new TMC5160Stepper(cs_id, _r_sense, _spi_index);
} else {
- log_info(" Unsupported Trinamic part number TMC" << _driver_part_number);
+ log_error(" Unsupported Trinamic part number TMC" << _driver_part_number);
_has_errors = true; // This motor cannot be used
return;
}
@@ -109,10 +109,10 @@ namespace MotorDrivers {
uint8_t result = tmc2130 ? tmc2130->test_connection() : tmc5160->test_connection();
switch (result) {
case 1:
- log_info(axisName() << " driver test failed. Check connection");
+ log_error(axisName() << " driver test failed. Check connection");
return false;
case 2:
- log_info(axisName() << " driver test failed. Check motor power");
+ log_error(axisName() << " driver test failed. Check motor power");
return false;
default:
// driver responded, so check for other errors from the DRV_STATUS register
diff --git a/FluidNC/src/Motors/TrinamicUartDriver.cpp b/FluidNC/src/Motors/TrinamicUartDriver.cpp
index bad9e7481..68e71ba92 100644
--- a/FluidNC/src/Motors/TrinamicUartDriver.cpp
+++ b/FluidNC/src/Motors/TrinamicUartDriver.cpp
@@ -83,7 +83,7 @@ namespace MotorDrivers {
tmc2209 = new TMC2209Stepper(_uart, _r_sense, _addr);
return false;
}
- log_info("Unsupported Trinamic motor p/n:" << _driver_part_number);
+ log_error("Unsupported Trinamic motor p/n:" << _driver_part_number);
return true;
}
@@ -103,10 +103,10 @@ namespace MotorDrivers {
uint8_t result = tmc2208 ? tmc2208->test_connection() : tmc2209->test_connection();
switch (result) {
case 1:
- log_info(" " << axisName() << " Trinamic driver test failed. Check connection");
+ log_error(" " << axisName() << " Trinamic driver test failed. Check connection");
return false;
case 2:
- log_info(" " << axisName() << " Trinamic driver test failed. Check motor power");
+ log_error(" " << axisName() << " Trinamic driver test failed. Check motor power");
return false;
default:
// driver responded, so check for other errors from the DRV_STATUS register
@@ -191,7 +191,7 @@ namespace MotorDrivers {
tmc2208->pwm_autoscale(true);
break;
default:
- log_info("Unsupported TMC2208 mode:" << _mode);
+ log_error("Unsupported TMC2208 mode:" << _mode);
}
} else {
switch (_mode) {
diff --git a/FluidNC/src/ProcessSettings.cpp b/FluidNC/src/ProcessSettings.cpp
index e5e3a3ed1..ee066cf0f 100644
--- a/FluidNC/src/ProcessSettings.cpp
+++ b/FluidNC/src/ProcessSettings.cpp
@@ -467,21 +467,20 @@ static Error xmodem_receive(const char* value, WebUI::AuthenticationLevel auth_l
if (!value || !*value) {
value = "uploaded";
}
- Print* outfile;
+ FileStream* outfile;
try {
outfile = new FileStream(value, "w");
} catch (...) {
log_info("Cannot open " << value);
return Error::UploadFailed;
}
- log_info("Receiving " << value << " via XModem");
int size = xmodemReceive(&Uart0, outfile);
- delete outfile;
if (size >= 0) {
- log_info("Received " << size << " bytes");
+ log_info("Received " << size << " bytes to file " << outfile->path());
} else {
log_info("Reception failed or was canceled");
}
+ delete outfile;
return size < 0 ? Error::UploadFailed : Error::Ok;
}
diff --git a/FluidNC/src/SettingsDefinitions.cpp b/FluidNC/src/SettingsDefinitions.cpp
index a6b4013c8..eb4915f08 100644
--- a/FluidNC/src/SettingsDefinitions.cpp
+++ b/FluidNC/src/SettingsDefinitions.cpp
@@ -48,5 +48,5 @@ void make_settings() {
config_filename = new StringSetting("Name of Configuration File", EXTENDED, WG, NULL, "Config/Filename", "config.yaml", 1, 50, NULL);
// GRBL Numbered Settings
- status_mask = new IntSetting(NULL, GRBL, WG, "10", "Report/Status", 1, 0, 3, NULL);
+ status_mask = new IntSetting("What to include in status report", GRBL, WG, "10", "Report/Status", 1, 0, 3, NULL);
}
diff --git a/FluidNC/src/Spindles/HuanyangSpindle.cpp b/FluidNC/src/Spindles/HuanyangSpindle.cpp
index 0bcdc568d..dd647143b 100644
--- a/FluidNC/src/Spindles/HuanyangSpindle.cpp
+++ b/FluidNC/src/Spindles/HuanyangSpindle.cpp
@@ -173,6 +173,10 @@ namespace Spindles {
// RPM is Hz * 60 sec/min. The maximum possible speed is 400 Hz so
// 400 * 60 = 24000 RPM.
+ if (dev_speed != 0 && (dev_speed < _minFrequency || dev_speed > _maxFrequency)) {
+ log_warn(name() << " requested freq " << (dev_speed) << " is outside of range (" << _minFrequency << "," << _maxFrequency << ")");
+ }
+
// There is a configuration register PD144 that scales the display to show the
// RPMs. It is nominally set to 3000 (= 50Hz * 60) for a 2-pole motor or
// 1500 for a 4-pole motor, but it can be set slightly lower to account for
@@ -222,10 +226,6 @@ namespace Spindles {
return [](const uint8_t* response, Spindles::VFD* vfd) -> bool {
uint16_t value = (response[4] << 8) | response[5];
-#ifdef DEBUG_VFD
- log_debug("VFD: Max frequency = " << value / 100 << "Hz " << value / 100 * 60 << "RPM");
-#endif
- log_info("VFD: Max speed:" << (value / 100 * 60) << "rpm");
// Set current RPM value? Somewhere?
auto huanyang = static_cast(vfd);
@@ -240,14 +240,15 @@ namespace Spindles {
return [](const uint8_t* response, Spindles::VFD* vfd) -> bool {
uint16_t value = (response[4] << 8) | response[5];
-#ifdef DEBUG_VFD
- log_debug("VFD: Min frequency = " << value / 100 << "Hz " << value / 100 * 60 << "RPM");
-#endif
- log_info("VFD: Min speed:" << (value / 100 * 60) << "rpm");
-
// Set current RPM value? Somewhere?
auto huanyang = static_cast(vfd);
huanyang->_minFrequency = value;
+
+ log_info(huanyang->name() << " PD005,PD011 Freq range (" << (huanyang->_minFrequency / 100) << ","
+ << (huanyang->_maxFrequency / 100) << ") Hz");
+ log_info(huanyang->name() << " RPM range (" << (huanyang->_minFrequency / 100 * 60) << ","
+ << (huanyang->_maxFrequency / 100 * 60) << ") RPM");
+
return true;
};
} else if (index == -3) {
@@ -257,13 +258,13 @@ namespace Spindles {
return [](const uint8_t* response, Spindles::VFD* vfd) -> bool {
uint16_t value = (response[4] << 8) | response[5];
-#ifdef DEBUG_VFD
- log_debug("VFD: Max rated revolutions @ 50Hz = " << value);
-#endif
+
// Set current RPM value? Somewhere?
auto huanyang = static_cast(vfd);
huanyang->_maxRpmAt50Hz = value;
+ log_info(huanyang->name() << " PD144 Rated RPM @ 50Hz:" << huanyang->_maxRpmAt50Hz);
+
// Regarding PD144, the 2 versions of the manuals both say "This is set according to the
// actual revolution of the motor. The displayed value is the same as this set value. It
// can be used as a monitoring parameter, which is convenient to the user. This set value
@@ -275,39 +276,36 @@ namespace Spindles {
return true;
};
}
- /*
- The number of poles seems to be over constrained information with PD144. If we're wrong, here's how
- to get this information. Note that you probably have to call 'updateRPM' here then:
- --
+
+ // The number of poles seems to be over constrained information with PD144. If we're wrong, here's how
+ // to get this information. Note that you probably have to call 'updateRPM' here then:
+ // --
else if (index == -4) {
// Number Poles
-
- data.msg[3] = 143; // PD143: 4 or 2 poles in motor. Default is 4. A spindle being 24000RPM@400Hz implies 2 poles
+ data.rx_length = 5;
+ data.msg[3] = 143; // PD143: 4 or 2 poles in motor. Default is 4. A spindle being 24000RPM@400Hz implies 2 poles
return [](const uint8_t* response, Spindles::VFD* vfd) -> bool {
- uint8_t value = response[4]; // Single byte response.
-
+ uint8_t value = response[4]; // Single byte response.
+ auto huanyang = static_cast(vfd);
// Sanity check. We expect something like 2 or 4 poles.
if (value <= 4 && value >= 2) {
-#ifdef DEBUG_VFD
// Set current RPM value? Somewhere?
- log_debug("VFD: Number of poles set to " << value);
-#endif
- auto huanyang = static_cast(vfd);
huanyang->_numberPoles = value;
+
+ log_info(huanyang->name() << " PD143 Poles:" << huanyang->_numberPoles);
+
+ huanyang->updateRPM();
+
return true;
- }
- else {
- error_all("Initialization of Huanyang spindle failed. Number of poles (PD143, expected 2-4, got %d) is not sane.",
- value);
+ } else {
+ log_error(huanyang->name() << " PD143 Poles: expected 2-4, got:" << value);
return false;
}
};
-
}
- */
// Done.
return nullptr;
@@ -332,8 +330,6 @@ namespace Spindles {
}
setupSpeeds(_maxFrequency);
_slop = std::max(_maxFrequency / 40, 1);
-
- // log_info("VFD: VFD settings read: RPM Range(" << _min_rpm << " , " << _max_rpm << ")]");
}
VFD::response_parser Huanyang::get_status_ok(ModbusCommand& data) {
diff --git a/FluidNC/src/Spindles/HuanyangSpindle.h b/FluidNC/src/Spindles/HuanyangSpindle.h
index fa675ae91..e92902a9f 100644
--- a/FluidNC/src/Spindles/HuanyangSpindle.h
+++ b/FluidNC/src/Spindles/HuanyangSpindle.h
@@ -15,7 +15,7 @@ namespace Spindles {
uint16_t _minFrequency = 0; // PD011: frequency lower limit. Normally 0.
uint16_t _maxFrequency = 400; // PD005: max frequency the VFD will allow. Normally 400.
uint16_t _maxRpmAt50Hz = 100; // PD144: rated motor revolution at 50Hz => 24000@400Hz = 3000@50HZ
- // uint16_t _numberPoles = 2; // PD143: 4 or 2 poles in motor. Default is 4. A spindle being 24000RPM@400Hz implies 2 poles
+ uint16_t _numberPoles = 2; // PD143: 4 or 2 poles in motor. Default is 4. A spindle being 24000RPM@400Hz implies 2 poles
void updateRPM();
diff --git a/FluidNC/src/Spindles/VFDSpindle.cpp b/FluidNC/src/Spindles/VFDSpindle.cpp
index 49eabe06a..88ba6fdd0 100644
--- a/FluidNC/src/Spindles/VFDSpindle.cpp
+++ b/FluidNC/src/Spindles/VFDSpindle.cpp
@@ -239,12 +239,12 @@ namespace Spindles {
if (retry_count == MAX_RETRIES) {
if (!unresponsive) {
- log_info("Spindle RS485 Unresponsive");
+ log_info("VFD RS485 Unresponsive");
unresponsive = true;
pollidx = -1;
}
if (next_cmd.critical) {
- log_error("Critical Spindle RS485 Unresponsive");
+ log_error("Critical VFD RS485 Unresponsive");
mc_reset();
rtAlarm = ExecAlarm::SpindleControl;
}
@@ -311,7 +311,7 @@ namespace Spindles {
bool critical = (sys.state == State::Cycle || state != SpindleState::Disable);
uint32_t dev_speed = mapSpeed(speed);
- log_debug("Speed:" << speed << " linearized:" << dev_speed);
+ log_debug("RPM:" << speed << " mapped to device units:" << dev_speed);
if (_current_state != state) {
// Changing state
@@ -361,7 +361,7 @@ namespace Spindles {
#endif
if (unchanged == limit) {
- log_error("Critical Spindle RS485 did not reach speed " << dev_speed << ". Reported speed is " << _sync_dev_speed);
+ log_error(name() << " spindle did not reach device units " << dev_speed << ". Reported value is " << _sync_dev_speed);
mc_reset();
rtAlarm = ExecAlarm::SpindleControl;
}
@@ -380,7 +380,7 @@ namespace Spindles {
if (mode == SpindleState::Disable) {
if (!xQueueReset(vfd_cmd_queue)) {
- log_info("VFD spindle off, queue could not be reset");
+ log_info(name() << " spindle off, queue could not be reset");
}
}
diff --git a/FluidNC/src/WebUI/WebClient.cpp b/FluidNC/src/WebUI/WebClient.cpp
index ecd718651..339669c21 100644
--- a/FluidNC/src/WebUI/WebClient.cpp
+++ b/FluidNC/src/WebUI/WebClient.cpp
@@ -21,16 +21,17 @@ namespace WebUI {
_header_sent = true;
}
- size_t remaining = length;
- while (remaining) {
- size_t copylen = std::min(remaining, BUFLEN - _buflen);
- memcpy(&_buffer[_buflen], buffer, copylen);
+ size_t index = 0;
+ while (index < length) {
+ size_t copylen = std::min(length - index, BUFLEN - _buflen);
+ memcpy(_buffer + _buflen, buffer + index, copylen);
_buflen += copylen;
- remaining -= copylen;
+ index += copylen;
if (_buflen >= BUFLEN) { // The > case should not happen
flush();
}
}
+
return length;
}
diff --git a/FluidNC/src/xmodem.cpp b/FluidNC/src/xmodem.cpp
index 3c04f2c25..d1a2cdd1c 100644
--- a/FluidNC/src/xmodem.cpp
+++ b/FluidNC/src/xmodem.cpp
@@ -175,8 +175,8 @@ int xmodemReceive(Uart* serial, Print* out) {
goto start_recv;
case EOT:
flush_packet(bufsz, len);
- flushinput();
_outbyte(ACK);
+ flushinput();
return len; /* normal end */
case CAN:
if ((c = _inbyte(DLY_1S)) == CAN) {
diff --git a/example_configs/6_pack_TMC5160_Huanyang.yaml b/example_configs/6_pack_TMC5160_Huanyang.yaml
new file mode 100644
index 000000000..7fc471108
--- /dev/null
+++ b/example_configs/6_pack_TMC5160_Huanyang.yaml
@@ -0,0 +1,192 @@
+board: 6 Pack
+name: 6 Pack TMC5160 XYZ
+stepping:
+ engine: I2S_STREAM
+ idle_ms: 255
+ pulse_us: 2
+ dir_delay_us: 1
+ disable_delay_us: 0
+
+axes:
+ shared_stepper_disable_pin: NO_PIN
+ x:
+ steps_per_mm: 800.000
+ max_rate_mm_per_min: 5000.000
+ acceleration_mm_per_sec2: 100.000
+ max_travel_mm: 300.000
+ soft_limits: false
+ homing:
+ cycle: 2
+ positive_direction: false
+ mpos_mm: 150.000
+ feed_mm_per_min: 100.000
+ seek_mm_per_min: 200.000
+ seek_scaler: 1.100
+ feed_scaler: 1.100
+
+ motor0:
+ limit_neg_pin: NO_PIN
+ limit_pos_pin: NO_PIN
+ limit_all_pin: gpio.33:pu
+ hard_limits: true
+ pulloff_mm:1.000
+ tmc_5160:
+ cs_pin: i2so.3
+ r_sense_ohms: 0.075
+ run_amps: 1.75
+ hold_amps: 0.50
+ microsteps: 16
+ stallguard: 0
+ stallguard_debug: false
+ toff_disable: 0
+ toff_stealthchop: 5
+ toff_coolstep: 3
+ run_mode: CoolStep
+ homing_mode: CoolStep
+ use_enable: false
+ step_pin: I2SO.2
+ direction_pin: I2SO.1
+ disable_pin: I2SO.0
+
+ y:
+ steps_per_mm: 800.000
+ max_rate_mm_per_min: 5000.000
+ acceleration_mm_per_sec2: 100.000
+ max_travel_mm: 300.000
+ soft_limits: false
+ homing:
+ cycle: 2
+ positive_direction: true
+ mpos_mm: 150.000
+ feed_mm_per_min: 100.000
+ seek_mm_per_min: 200.000
+ seek_scaler: 1.100
+ feed_scaler: 1.100
+
+ motor0:
+ limit_neg_pin: NO_PIN
+ limit_pos_pin: NO_PIN
+ limit_all_pin: gpio.32:pu
+ hard_limits: true
+ pulloff_mm:1.000
+ tmc_5160:
+ cs_pin: i2so.6
+ r_sense_ohms: 0.075
+ run_amps: 1.75
+ hold_amps: 0.50
+ microsteps: 16
+ stallguard: 0
+ stallguard_debug: false
+ toff_disable: 0
+ toff_stealthchop: 5
+ toff_coolstep: 3
+ run_mode: StealthChop
+ homing_mode: StealthChop
+ use_enable: false
+ step_pin: I2SO.5
+ direction_pin: I2SO.4
+ disable_pin: I2SO.7
+
+ z:
+ steps_per_mm: 800.000
+ max_rate_mm_per_min: 5000.000
+ acceleration_mm_per_sec2: 100.000
+ max_travel_mm: 300.000
+ soft_limits: false
+ homing:
+ cycle: 1
+ positive_direction: true
+ mpos_mm: 150.000
+ feed_mm_per_min: 100.000
+ seek_mm_per_min: 800.000
+ seek_scaler: 1.100
+ feed_scaler: 1.100
+
+ motor0:
+ limit_neg_pin: NO_PIN
+ limit_pos_pin: NO_PIN
+ limit_all_pin: gpio.35
+ hard_limits: true
+ pulloff_mm:1.000
+ tmc_5160:
+ cs_pin: i2so.11
+ r_sense_ohms: 0.075
+ run_amps: 1.750
+ hold_amps: 0.50
+ microsteps: 16
+ stallguard: 0
+ stallguard_debug: false
+ toff_disable: 0
+ toff_stealthchop: 5
+ toff_coolstep: 3
+ run_mode: StealthChop
+ homing_mode: StealthChop
+ use_enable: false
+ step_pin: I2SO.10
+ direction_pin: I2SO.9
+ disable_pin: I2SO.8
+
+i2so:
+ bck_pin: gpio.22
+ data_pin: gpio.21
+ ws_pin: gpio.17
+
+spi:
+ miso_pin: gpio.19
+ mosi_pin: gpio.23
+ sck_pin: gpio.18
+
+sdcard:
+ card_detect_pin: NO_PIN
+ cs_pin: gpio.5
+
+control:
+ safety_door_pin: NO_PIN
+ reset_pin: NO_PIN
+ feed_hold_pin: NO_PIN
+ cycle_start_pin: NO_PIN
+ macro0_pin: NO_PIN
+ macro1_pin: NO_PIN
+ macro2_pin: NO_PIN
+ macro3_pin: NO_PIN
+
+probe:
+ pin: NO_PIN
+ check_mode_start: true
+
+macros:
+ startup_line0:
+ startup_line1:
+ macro0:
+ macro1:
+ macro2:
+ macro3:
+
+user_outputs:
+ analog0_pin: NO_PIN
+ analog1_pin: NO_PIN
+ analog2_pin: NO_PIN
+ analog3_pin: NO_PIN
+ analog0_hz: 5000
+ analog1_hz: 5000
+ analog2_hz: 5000
+ analog3_hz: 5000
+ digital0_pin: NO_PIN
+ digital1_pin: NO_PIN
+ digital2_pin: NO_PIN
+ digital3_pin: NO_PIN
+
+start:
+ must_home: false
+
+Huanyang:
+ uart:
+ txd_pin: gpio.26
+ rxd_pin: gpio.16
+ rts_pin: gpio.4
+ baud: 9600
+ mode: 8N1
+ modbus_id: 1
+ tool_num: 0
+ speed_map: 0=0% 1000=0% 24000=100%
+