Skip to content

Commit

Permalink
Merge pull request #1013 from bdring/Devt
Browse files Browse the repository at this point in the history
Devt
  • Loading branch information
bdring authored Sep 4, 2023
2 parents da54111 + 5b5198c commit 7c65125
Show file tree
Hide file tree
Showing 30 changed files with 189 additions and 125 deletions.
2 changes: 1 addition & 1 deletion FluidNC/esp32/sdspi.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -12,7 +12,7 @@
#define CHECK_EXECUTE_RESULT(err, str) \
do { \
if ((err) != ESP_OK) { \
log_error(str << " code 0x" << to_hex(err)); \
log_error(str << " code " << to_hex(err)); \
goto cleanup; \
} \
} while (0)
Expand Down
4 changes: 2 additions & 2 deletions FluidNC/esp32/tmc_spi.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -43,7 +43,7 @@
// This is executed in the object context so it has access to class
// data such as the CS pin that switchCSpin() uses
void TMC2130Stepper::write(uint8_t reg, uint32_t data) {
log_verbose("TMC reg 0x" << to_hex(reg) << " write 0x" << to_hex(data));
log_verbose("TMC reg " << to_hex(reg) << " write " << to_hex(data));
tmc_spi_bus_setup();

switchCSpin(0);
Expand Down Expand Up @@ -88,7 +88,7 @@ uint32_t TMC2130Stepper::read(uint8_t reg) {
data += (uint32_t)in[dummy_in_bytes + 4];
switchCSpin(1);

log_verbose("TMC reg 0x" << to_hex(reg) << " read 0x" << to_hex(data) << " status 0x" << to_hex(status));
log_verbose("TMC reg " << to_hex(reg) << " read " << to_hex(data) << " status " << to_hex(status));

return data;
}
1 change: 1 addition & 0 deletions FluidNC/src/Error.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -68,6 +68,7 @@ std::map<Error, const char*> ErrorNames = {
{ Error::AuthenticationFailed, "Authentication failed!" },
{ Error::Eol, "End of line" },
{ Error::Eof, "End of file" },
{ Error::Reset, "System Reset" },
{ Error::AnotherInterfaceBusy, "Another interface is busy" },
{ Error::BadPinSpecification, "Bad Pin Specification" },
{ Error::JogCancelled, "Jog Cancelled" },
Expand Down
1 change: 1 addition & 0 deletions FluidNC/src/Error.h
Original file line number Diff line number Diff line change
Expand Up @@ -72,6 +72,7 @@ enum class Error : uint8_t {
AuthenticationFailed = 110,
Eol = 111,
Eof = 112, // Not necessarily an error
Reset = 113,
AnotherInterfaceBusy = 120,
JogCancelled = 130,
BadPinSpecification = 150,
Expand Down
3 changes: 3 additions & 0 deletions FluidNC/src/GCode.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1620,6 +1620,9 @@ Error gc_execute_line(char* line) {
// As far as the parser is concerned, the position is now == target. In reality the
// motion control system might still be processing the action and the real tool position
// in any intermediate location.
if (sys.abort) {
return Error::Reset;
}
if (gc_update_pos == GCUpdatePos::Target) {
copyAxes(gc_state.position, gc_block.values.xyz);
} else if (gc_update_pos == GCUpdatePos::System) {
Expand Down
2 changes: 1 addition & 1 deletion FluidNC/src/I2SOut.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -887,7 +887,7 @@ int i2s_out_init(i2s_out_init_t& init_param) {
"I2SOutTask",
4096,
NULL,
1,
3,
nullptr,
CONFIG_ARDUINO_RUNNING_CORE // must run the task on same core
);
Expand Down
1 change: 1 addition & 0 deletions FluidNC/src/InputFile.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -88,6 +88,7 @@ void InputFile::stopJob() {
//Report print stopped
_notifyf("File print canceled", "Reset during file job at line: %d", getLineNumber());
log_info("Reset during file job at line: " << getLineNumber());
_progress = "";
allChannels.kill(this);
}

Expand Down
11 changes: 7 additions & 4 deletions FluidNC/src/Kinematics/ParallelDelta.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -60,10 +60,10 @@ namespace Kinematics {
const float tan30 = 1.0 / sqrt3;

// the geometry of the delta
float rf; // radius of the fixed side (length of motor cranks)
float re; // radius of end effector side (length of linkages)
float f; // sized of fixed side triangel
float e; // size of end effector side triangle
float rf; // radius of the fixed side (length of motor cranks)
float re; // radius of end effector side (length of linkages)
float f; // sized of fixed side triangel
float e; // size of end effector side triangle

static float last_angle[MAX_N_AXIS] = { 0.0 }; // A place to save the previous motor angles for distance/feed rate calcs
static float last_cartesian[MAX_N_AXIS] = { 0.0 }; // A place to save the previous motor angles for distance/feed rate calcs
Expand Down Expand Up @@ -196,6 +196,9 @@ namespace Kinematics {
float segment_dist = dist / ((float)segment_count); // distance of each segment...will be used for feedrate conversion

for (uint32_t segment = 1; segment <= segment_count; segment++) {
if (sys.abort) {
return true;
}
//log_debug("Segment:" << segment << " of " << segment_count);
// determine this segment's target
seg_target[X_AXIS] = position[X_AXIS] + (dx / float(segment_count) * segment);
Expand Down
3 changes: 3 additions & 0 deletions FluidNC/src/Kinematics/WallPlotter.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -99,6 +99,9 @@ namespace Kinematics {

// Calculate desired cartesian feedrate distance ratio. Same for each seg.
for (uint32_t segment = 1; segment <= segment_count; segment++) {
if (sys.abort) {
return true;
}
// calculate the cartesian end point of the next segment
for (size_t axis = X_AXIS; axis < n_axis; axis++) {
cartesian_segment_end[axis] += cartesian_segment_components[axis];
Expand Down
24 changes: 13 additions & 11 deletions FluidNC/src/Machine/Macros.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -6,20 +6,17 @@
#include "src/System.h" // sys
#include "src/Machine/MachineConfig.h" // config

Macro::Macro(const char* name) : _name(name) {}

void MacroEvent::run(void* arg) {
int n = int(arg);
if (sys.state != State::Idle) {
log_error("Macro can only be used in idle state");
return;
}
config->_macros->_macro[n].run();
config->_macros->_macro[_num].run();
}

Macro Macros::_startup_line[n_startup_lines] = { { "startup_line0" }, { "startup_line1" } };
Macro Macros::_macro[n_macros] = { { "macro0" }, { "macro1" }, { "macro2" }, { "macro3" } };
Macro Macros::_after_homing = { "after_homing" };
Macro Macros::_after_reset = { "after_reset" };
Macro Macros::_after_unlock = { "after_unlock" };
Macro Macros::_startup_line[n_startup_lines] = { "startup_line0", "startup_line1" };
Macro Macros::_macro[n_macros] = { "macro0", "macro1", "macro2", "macro3", "macro4" };
Macro Macros::_after_homing { "after_homing" };
Macro Macros::_after_reset { "after_reset" };
Macro Macros::_after_unlock { "after_unlock" };

MacroEvent macro0Event { 0 };
MacroEvent macro1Event { 1 };
Expand Down Expand Up @@ -54,6 +51,11 @@ Cmd findOverride(std::string name) {
}

bool Macro::run() {
if (sys.state != State::Idle) {
log_error("Macro can only be used in idle state");
return false;
}

const std::string& s = _gcode;
if (_gcode == "") {
return true;
Expand Down
24 changes: 12 additions & 12 deletions FluidNC/src/Machine/Macros.h
Original file line number Diff line number Diff line change
Expand Up @@ -27,15 +27,15 @@ namespace Machine {
class Macro {
public:
std::string _gcode;
std::string _name;
Macro(const char* name) : _name(name) {}
const char* _name;
Macro(const char* name);
bool run();
};

class Macros : public Configuration::Configurable {
public:
static const int n_startup_lines = 2;
static const int n_macros = 4;
static const int n_macros = 5;

static Macro _macro[n_macros];
static Macro _startup_line[n_startup_lines];
Expand All @@ -50,15 +50,15 @@ namespace Machine {
// TODO: We could validate the startup lines

void group(Configuration::HandlerBase& handler) override {
handler.item(_startup_line[0]._name.c_str(), _startup_line[0]._gcode);
handler.item(_startup_line[1]._name.c_str(), _startup_line[1]._gcode);
handler.item(_macro[0]._name.c_str(), _macro[0]._gcode);
handler.item(_macro[1]._name.c_str(), _macro[1]._gcode);
handler.item(_macro[2]._name.c_str(), _macro[2]._gcode);
handler.item(_macro[3]._name.c_str(), _macro[3]._gcode);
handler.item(_after_homing._name.c_str(), _after_homing._gcode);
handler.item(_after_reset._name.c_str(), _after_reset._gcode);
handler.item(_after_unlock._name.c_str(), _after_unlock._gcode);
handler.item(_startup_line[0]._name, _startup_line[0]._gcode);
handler.item(_startup_line[1]._name, _startup_line[1]._gcode);
handler.item(_macro[0]._name, _macro[0]._gcode);
handler.item(_macro[1]._name, _macro[1]._gcode);
handler.item(_macro[2]._name, _macro[2]._gcode);
handler.item(_macro[3]._name, _macro[3]._gcode);
handler.item(_after_homing._name, _after_homing._gcode);
handler.item(_after_reset._name, _after_reset._gcode);
handler.item(_after_unlock._name, _after_unlock._gcode);
}

~Macros() {}
Expand Down
1 change: 1 addition & 0 deletions FluidNC/src/Main.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -138,6 +138,7 @@ void setup() {
}

void loop() {
vTaskPrioritySet(NULL, 2);
static int tries = 0;
try {
// Start the main loop. Processes program inputs and executes them.
Expand Down
6 changes: 0 additions & 6 deletions FluidNC/src/MotionControl.h
Original file line number Diff line number Diff line change
Expand Up @@ -19,12 +19,6 @@ extern bool probe_succeeded; // Tracks if last probing cycle was successful.
// System motion commands must have a line number of zero.
const int PARKING_MOTION_LINE_NUMBER = 0;

// Execute linear motion in absolute millimeter coordinates. Feed rate given in millimeters/second
// unless invert_feed_rate is true. Then the feed_rate means that the motion should be completed in
// (1 minute)/feed_rate time.
bool cartesian_to_motors(float* target, plan_line_data_t* pl_data, float* position);
void motors_to_cartesian(float* cartesian, float* motors, int n_axis);

// Execute a linear motion in cartesian space.
bool mc_linear(float* target, plan_line_data_t* pl_data, float* position);

Expand Down
14 changes: 7 additions & 7 deletions FluidNC/src/Motors/TMC2209Driver.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -80,13 +80,13 @@ namespace MotorDrivers {
}

// dump the registers. This is helpful for people migrating to the Pro version
log_verbose("CHOPCONF: 0x" << to_hex(tmc2209->CHOPCONF()));
log_verbose("COOLCONF: 0x" << to_hex(tmc2209->COOLCONF()));
log_verbose("TPWMTHRS: 0x" << to_hex(tmc2209->TPWMTHRS()));
log_verbose("TCOOLTHRS: 0x" << to_hex(tmc2209->TCOOLTHRS()));
log_verbose("GCONF: 0x" << to_hex(tmc2209->GCONF()));
log_verbose("PWMCONF: 0x" << to_hex(tmc2209->PWMCONF()));
log_verbose("IHOLD_IRUN: 0x" << to_hex(tmc2209->IHOLD_IRUN()));
log_verbose("CHOPCONF: " << to_hex(tmc2209->CHOPCONF()));
log_verbose("COOLCONF: " << to_hex(tmc2209->COOLCONF()));
log_verbose("TPWMTHRS: " << to_hex(tmc2209->TPWMTHRS()));
log_verbose("TCOOLTHRS: " << to_hex(tmc2209->TCOOLTHRS()));
log_verbose("GCONF: " << to_hex(tmc2209->GCONF()));
log_verbose("PWMCONF: " << to_hex(tmc2209->PWMCONF()));
log_verbose("IHOLD_IRUN: " << to_hex(tmc2209->IHOLD_IRUN()));

_cs_pin.synchronousWrite(false);
}
Expand Down
14 changes: 7 additions & 7 deletions FluidNC/src/Motors/TMC5160Driver.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -80,13 +80,13 @@ namespace MotorDrivers {
}
}
// dump the registers. This is helpful for people migrating to the Pro version
log_verbose("CHOPCONF: 0x" << to_hex(tmc5160->CHOPCONF()));
log_verbose("COOLCONF: 0x" << to_hex(tmc5160->COOLCONF()));
log_verbose("THIGH: 0x" << to_hex(tmc5160->THIGH()));
log_verbose("TCOOLTHRS: 0x" << to_hex(tmc5160->TCOOLTHRS()));
log_verbose("GCONF: 0x" << to_hex(tmc5160->GCONF()));
log_verbose("PWMCONF: 0x" << to_hex(tmc5160->PWMCONF()));
log_verbose("IHOLD_IRUN: 0x" << to_hex(tmc5160->IHOLD_IRUN()));
log_verbose("CHOPCONF: " << to_hex(tmc5160->CHOPCONF()));
log_verbose("COOLCONF: " << to_hex(tmc5160->COOLCONF()));
log_verbose("THIGH: " << to_hex(tmc5160->THIGH()));
log_verbose("TCOOLTHRS: " << to_hex(tmc5160->TCOOLTHRS()));
log_verbose("GCONF: " << to_hex(tmc5160->GCONF()));
log_verbose("PWMCONF: " << to_hex(tmc5160->PWMCONF()));
log_verbose("IHOLD_IRUN: " << to_hex(tmc5160->IHOLD_IRUN()));
}

// Report diagnostic and tuning info
Expand Down
4 changes: 2 additions & 2 deletions FluidNC/src/Motors/TrinamicBase.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -106,7 +106,7 @@ namespace MotorDrivers {

bool TrinamicBase::checkVersion(uint8_t expected, uint8_t got) {
if (expected != got) {
log_error(axisName() << " TMC driver not detected - expected 0x" << to_hex(expected) << " got 0x" << to_hex(got));
log_error(axisName() << " TMC driver not detected - expected " << to_hex(expected) << " got " << to_hex(got));
return false;
}
log_info(axisName() << " driver test passed");
Expand Down Expand Up @@ -146,7 +146,7 @@ namespace MotorDrivers {
// Display the stepper library version message once, before the first
// TMC config message.
if (_instances.empty()) {
log_debug("TMCStepper Library Ver. 0x" << to_hex(TMCSTEPPER_VERSION));
log_debug("TMCStepper Library Ver. " << to_hex(TMCSTEPPER_VERSION));
auto timer = xTimerCreate("Stallguard", 200, true, nullptr, read_sg);
// Timer failure is not fatal because you can still use the system
if (!timer) {
Expand Down
2 changes: 1 addition & 1 deletion FluidNC/src/OLED.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -67,7 +67,7 @@ void OLED::init() {
if (_error) {
return;
}
log_info("OLED I2C address:" << to_hex(_address) << " width: " << _width << " height: " << _height);
log_info("OLED I2C address: " << to_hex(_address) << " width: " << _width << " height: " << _height);
_oled = new SSD1306_I2C(_address, _geometry, config->_i2c[_i2c_num], 400000);
_oled->init();

Expand Down
33 changes: 25 additions & 8 deletions FluidNC/src/Protocol.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -156,8 +156,9 @@ void send_line(Channel& channel, const std::string& line) {

void output_loop(void* unused) {
while (true) {
// Block until a message is received
LogMessage message;
if (xQueueReceive(message_queue, &message, 0)) {
if (xQueueReceive(message_queue, &message, portMAX_DELAY)) {
if (message.isString) {
std::string* s = static_cast<std::string*>(message.line);
message.channel->println(s->c_str());
Expand All @@ -167,7 +168,6 @@ void output_loop(void* unused) {
message.channel->println(cp);
}
}
vTaskDelay(0);
}
}

Expand Down Expand Up @@ -222,7 +222,7 @@ void start_polling() {
16000,
// 8192, // size of task stack
0, // parameters
1, // priority
2, // priority
&outputTask, // task handle
SUPPORT_TASK_CORE // core
);
Expand All @@ -239,7 +239,9 @@ static void check_startup_state() {}

const uint32_t heapWarnThreshold = 15000;

uint32_t heapLowWater = UINT_MAX;
uint32_t heapLowWater = UINT_MAX;
uint32_t heapLowWaterReported = UINT_MAX;
int32_t heapLowWaterReportTime = 0;
void protocol_main_loop() {
start_polling();

Expand All @@ -257,7 +259,10 @@ void protocol_main_loop() {
Error status_code = execute_line(activeLine, *activeChannel, WebUI::AuthenticationLevel::LEVEL_GUEST);

// Tell the channel that the line has been processed.
activeChannel->ack(status_code);
// If the line was aborted, the channel could be invalid
if (!sys.abort) {
activeChannel->ack(status_code);
}

// Tell the input polling task that the line has been processed,
// so it can give us another one when available
Expand All @@ -268,8 +273,7 @@ void protocol_main_loop() {
protocol_auto_cycle_start();
protocol_execute_realtime(); // Runtime command check point.
if (sys.abort) {
stop_polling();
return; // Bail to main() program loop to reset system.
sys.abort = false;
}

// check to see if we should disable the stepper drivers
Expand All @@ -290,8 +294,20 @@ void protocol_main_loop() {
uint32_t newHeapSize = xPortGetFreeHeapSize();
if (newHeapSize < heapLowWater) {
heapLowWater = newHeapSize;
if (heapLowWater < heapWarnThreshold) {
}
// Consider reporting when the minimum has not yet been reported and it is low enough.
if (heapLowWater < heapLowWaterReported && heapLowWater < heapWarnThreshold) {
// typecast to uint32_t handles roll-over for this case
uint32_t ticksSinceReported = (getCpuTicks() - heapLowWaterReportTime);
uint32_t tickLimit = usToCpuTicks(200000);
// Report only if it has been a while since the last report or if the memory has
// dropped significantly (2k bytes) since the last report.
// This prevents a cycle where the reporting itself consumes some heap and triggers another
// report, but the true minimum is reported eventually, and large drops are reported immediately.
if ((heapLowWater < heapLowWaterReported - 2048) || (ticksSinceReported > tickLimit)) {
log_warn("Low memory: " << heapLowWater << " bytes");
heapLowWaterReported = heapLowWater;
heapLowWaterReportTime = getCpuTicks();
}
}
}
Expand Down Expand Up @@ -795,6 +811,7 @@ static void protocol_do_late_reset() {

// do we need to stop a running file job?
allChannels.stopJob();
sys.abort = true;
}

void protocol_exec_rt_system() {
Expand Down
Loading

0 comments on commit 7c65125

Please sign in to comment.