Skip to content

Commit

Permalink
Merge pull request #916 from bdring/Devt
Browse files Browse the repository at this point in the history
Devt
  • Loading branch information
bdring authored Jun 8, 2023
2 parents 76bc1ff + f8474da commit e87fc78
Show file tree
Hide file tree
Showing 34 changed files with 715 additions and 349 deletions.
Binary file modified FluidNC/data/index.html.gz
Binary file not shown.
35 changes: 35 additions & 0 deletions FluidNC/esp32/coredump.c
Original file line number Diff line number Diff line change
@@ -0,0 +1,35 @@
// Copyright 2022 Mitch Bradley
// Use of this source code is governed by a GPLv3 license that can be found in the LICENSE file.
//
// Noop replacements for ESP-IDF coredump routines.
// This suppresses complaints about not being able to find a coredump partition.
// We don't want to waste space for such a partition, and the Arduino Framework
// enables coredumps. We override that by stubbing out these routines.

#include <stddef.h>
#include "esp_err.h"
#include "esp_private/panic_internal.h"
#include "esp_core_dump_summary_port.h"

#ifdef __cplusplus
extern "C" {
#endif

void esp_core_dump_init(void) {}

void esp_core_dump_flash_init(void) {}
void esp_core_dump_to_flash(void* info) {}

esp_err_t esp_core_dump_image_check(void) {
return ESP_ERR_NOT_FOUND;
}
esp_err_t esp_core_dump_image_get(size_t* out_addr, size_t* out_size) {
return ESP_ERR_NOT_FOUND;
}
esp_err_t esp_core_dump_image_erase(void) {
return ESP_OK;
}

#ifdef __cplusplus
}
#endif
174 changes: 97 additions & 77 deletions FluidNC/esp32/gpio.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -40,24 +40,10 @@ void gpio_mode(pinnum_t pin, bool input, bool output, bool pullup, bool pulldown
}
gpio_config(&conf);
}
void IRAM_ATTR gpio_set_interrupt_type(pinnum_t pin, int mode) {
gpio_int_type_t type = GPIO_INTR_DISABLE;
// Do not use switch here because it is not IRAM_ATTR safe
if (mode == Pin::RISING_EDGE) {
type = GPIO_INTR_POSEDGE;
} else if (mode == Pin::FALLING_EDGE) {
type = GPIO_INTR_NEGEDGE;
} else if (mode == Pin::EITHER_EDGE) {
type = GPIO_INTR_ANYEDGE;
}
gpio_set_intr_type((gpio_num_t)pin, type);
}

#if 0
void gpio_add_interrupt(pinnum_t pin, int mode, void (*callback)(void*), void* arg) {
gpio_install_isr_service(ESP_INTR_FLAG_IRAM); // Will return an err if already called

gpio_set_interrupt_type(pin, mode);

gpio_num_t gpio = (gpio_num_t)pin;
gpio_isr_handler_add(gpio, callback, arg);

Expand All @@ -81,6 +67,100 @@ void gpio_route(pinnum_t pin, uint32_t signal) {
gpio_set_direction(gpio, (gpio_mode_t)GPIO_MODE_DEF_OUTPUT);
gpio_matrix_out(gpio, signal, 0, 0);
}
#endif

typedef uint64_t gpio_mask_t;

// Can be used to display gpio_mask_t data for debugging
static const char* g_to_hex(gpio_mask_t n) {
static char hexstr[24];
snprintf(hexstr, 22, "0x%llx", n);
return hexstr;
}

static gpio_mask_t gpios_inverted = 0; // GPIOs that are active low
static gpio_mask_t gpios_interest = 0; // GPIOs with an action
static gpio_mask_t gpios_current = 0; // The last GPIO action events that were sent

static int32_t gpio_next_event_ticks[GPIO_NUM_MAX + 1] = { 0 };
static int32_t gpio_deltat_ticks[GPIO_NUM_MAX + 1] = { 0 };

// Do not send events for changes that occur too soon
static void gpio_set_rate_limit(int gpio_num, uint32_t ms) {
gpio_deltat_ticks[gpio_num] = ms * portTICK_PERIOD_MS;
}

static inline gpio_mask_t get_gpios() {
return ((((uint64_t)REG_READ(GPIO_IN1_REG)) << 32) | REG_READ(GPIO_IN_REG)) ^ gpios_inverted;
}
static gpio_mask_t gpio_mask(int gpio_num) {
return 1ULL << gpio_num;
}
static inline bool gpio_is_active(int gpio_num) {
return get_gpios() & gpio_mask(gpio_num);
}
static void gpios_update(gpio_mask_t& gpios, int gpio_num, bool active) {
if (active) {
gpios |= gpio_mask(gpio_num);
} else {
gpios &= ~gpio_mask(gpio_num);
}
}

static gpio_dispatch_t gpioActions[GPIO_NUM_MAX + 1] = { nullptr };
static void* gpioArgs[GPIO_NUM_MAX + 1];

void gpio_set_action(int gpio_num, gpio_dispatch_t action, void* arg, bool invert) {
gpioActions[gpio_num] = action;
gpioArgs[gpio_num] = arg;
gpio_mask_t mask = gpio_mask(gpio_num);
gpios_update(gpios_interest, gpio_num, true);
gpios_update(gpios_inverted, gpio_num, invert);
gpio_set_rate_limit(gpio_num, 5);
bool active = gpio_is_active(gpio_num);

// Set current to the opposite of the current state so the first poll will send the current state
gpios_update(gpios_current, gpio_num, !active);
}
void gpio_clear_action(int gpio_num) {
gpioActions[gpio_num] = nullptr;
gpioArgs[gpio_num] = nullptr;
gpios_update(gpios_interest, gpio_num, false);
}

static void gpio_send_action(int gpio_num, bool active) {
auto end_ticks = gpio_next_event_ticks[gpio_num];
int32_t this_ticks = int32_t(xTaskGetTickCount());
if (end_ticks == 0 || ((this_ticks - end_ticks) > 0)) {
end_ticks = this_ticks + gpio_deltat_ticks[gpio_num];
if (end_ticks == 0) {
end_ticks = 1;
}
gpio_next_event_ticks[gpio_num] = end_ticks;

gpio_dispatch_t action = gpioActions[gpio_num];
if (action) {
action(gpio_num, gpioArgs[gpio_num], active);
}
gpios_update(gpios_current, gpio_num, active);
}
}

void poll_gpios() {
gpio_mask_t gpios_active = get_gpios();
gpio_mask_t gpios_changed = (gpios_active ^ gpios_current) & gpios_interest;
if (gpios_changed) {
int zeros;
while ((zeros = __builtin_clzll(gpios_changed)) != 64) {
int gpio_num = 63 - zeros;
gpio_send_action(gpio_num, gpios_active & gpio_mask(gpio_num));
// Remove bit from mask so clzll will find the next one
gpios_update(gpios_changed, gpio_num, false);
}
}
}

// Support functions for gpio_dump
static bool exists(gpio_num_t gpio) {
if (gpio == 20) {
// GPIO20 is listed in GPIO_PIN_MUX_REG[] but it is only
Expand Down Expand Up @@ -378,7 +458,7 @@ struct gpio_matrix_t {
{ 228, "", "ig_in_func228", false },
{ -1, "", "", false } };

const char* out_sel_name(int function) {
static const char* out_sel_name(int function) {
gpio_matrix_t* p;
for (p = gpio_matrix; p->num != -1; ++p) {
if (p->num == function) {
Expand All @@ -388,7 +468,7 @@ const char* out_sel_name(int function) {
return "";
}

void show_matrix(Print& out) {
static void show_matrix(Print& out) {
gpio_matrix_t* p;
for (p = gpio_matrix; p->num != -1; ++p) {
uint32_t in_sel = gpio_in_sel(p->num);
Expand Down Expand Up @@ -432,63 +512,3 @@ void gpio_dump(Print& out) {
out << "Input Matrix\n";
show_matrix(out);
}

typedef uint64_t gpio_mask_t;
static gpio_mask_t gpio_inverts = 0;
static gpio_mask_t gpio_interest = 0;
static gpio_mask_t gpio_current = 0;
void IRAM_ATTR check_switches() {
gpio_mask_t gpio_this = (((uint64_t)REG_READ(GPIO_IN_REG)) << 32) | REG_READ(GPIO_IN1_REG);
if (gpio_this != gpio_current) {
gpio_mask_t gpio_changes = (gpio_this ^ gpio_current) & gpio_interest;
int bitno;
while (bitno = __builtin_ffsll(gpio_changes)) {
--bitno;
bool isActive = (gpio_this ^ gpio_inverts) & (1ULL << bitno);
// protocol_send_event_from_ISR(&pin_changes, (void*)(isActive ? bitno : -bitno));
protocol_send_event_from_ISR(&motionCancelEvent, (void*)(isActive ? bitno : -bitno));
}
gpio_current = gpio_this;
}
++gpio_interest;
}
static gpio_dispatch_t gpioActions[GPIO_NUM_MAX + 1];
static void* gpioArgs[GPIO_NUM_MAX + 1];
void gpio_set_action(int gpio_num, gpio_dispatch_t action, void* arg, bool invert) {
gpioActions[gpio_num] = action;
gpioArgs[gpio_num] = arg;
gpio_mask_t mask = 1ULL << gpio_num;
gpio_interest |= mask;
if (invert) {
gpio_inverts |= mask;
} else {
gpio_inverts &= ~mask;
}
}
void gpio_clear_action(int gpio_num) {
gpioActions[gpio_num] = nullptr;
gpioArgs[gpio_num] = nullptr;
gpio_mask_t mask = 1ULL << gpio_num;
gpio_interest &= ~mask;
}
void poll_gpios() {
gpio_mask_t gpio_this = (((uint64_t)REG_READ(GPIO_IN1_REG)) << 32) | REG_READ(GPIO_IN_REG);

gpio_mask_t gpio_changes = (gpio_this ^ gpio_current) & gpio_interest;
if (gpio_changes) {
gpio_mask_t gpio_active = gpio_this ^ gpio_inverts;
int zeros;
while ((zeros = __builtin_clzll(gpio_changes)) != 64) {
int gpio_num = 63 - zeros;
gpio_mask_t mask = 1ULL << gpio_num;
bool isActive = gpio_active & mask;
// Uart0 << gpio_num << " " << isActive << "\n";
gpio_dispatch_t action = gpioActions[gpio_num];
if (action) {
action(gpio_num, gpioArgs[gpio_num], isActive);
}
gpio_changes &= ~mask;
}
}
gpio_current = gpio_this;
}
2 changes: 1 addition & 1 deletion FluidNC/include/Driver/sdspi.h
Original file line number Diff line number Diff line change
Expand Up @@ -4,4 +4,4 @@ bool sd_init_slot(uint32_t freq_hz, int cs_pin, int cd_pin = -1, int wp_pin = -1
void sd_unmount();
void sd_deinit_slot();

std::error_code sd_mount(int max_files = 5);
std::error_code sd_mount(int max_files = 1);
11 changes: 7 additions & 4 deletions FluidNC/src/Channel.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -92,14 +92,17 @@ static bool motionState() {
void Channel::autoReport() {
if (_reportInterval) {
auto limitState = limits_get_state();
if (_reportWco || sys.state != _lastState || limitState != _lastLimits ||
auto probeState = config->_probe->get_state();
if (_reportWco || sys.state != _lastState || limitState != _lastLimits || probeState != _lastProbe ||
(motionState() && (int32_t(xTaskGetTickCount()) - _nextReportTime) >= 0)) {
if (_reportWco) {
report_wco_counter = 0;
}
_reportWco = false;
_lastState = sys.state;
_lastLimits = limitState;
_reportWco = false;
_lastState = sys.state;
_lastLimits = limitState;
_lastProbe = probeState;

_nextReportTime = xTaskGetTickCount() + _reportInterval;
report_realtime_status(*this);
}
Expand Down
1 change: 1 addition & 0 deletions FluidNC/src/Channel.h
Original file line number Diff line number Diff line change
Expand Up @@ -45,6 +45,7 @@ class Channel : public Stream {
float _lastFeedRate;
State _lastState;
MotorMask _lastLimits;
bool _lastProbe;

bool _reportWco = true;
CoordIndex _reportNgc = CoordIndex::End;
Expand Down
3 changes: 2 additions & 1 deletion FluidNC/src/Configuration/Parser.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -38,7 +38,8 @@ namespace Configuration {
return result;
}

StringRange Parser::stringValue() const { return StringRange(token_.sValueStart_, token_.sValueEnd_); }
// String values might have meaningful leading and trailing spaces so we avoid trimming the string (false)
StringRange Parser::stringValue() const { return StringRange(token_.sValueStart_, token_.sValueEnd_, false); }

bool Parser::boolValue() const {
auto str = StringRange(token_.sValueStart_, token_.sValueEnd_);
Expand Down
1 change: 0 additions & 1 deletion FluidNC/src/ControlPin.h
Original file line number Diff line number Diff line change
@@ -1,7 +1,6 @@
#pragma once

#include "Pin.h"
#include <esp_attr.h> // IRAM_ATTR
#include "Machine/EventPin.h"
namespace Machine {
class ControlPin : public Machine::EventPin {
Expand Down
8 changes: 8 additions & 0 deletions FluidNC/src/FluidPath.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -5,6 +5,8 @@
#include "Driver/sdspi.h"
#include "Driver/localfs.h"
#include "Config.h"
#include "Error.h"
#include "HashFS.h"

int FluidPath::_refcnt = 0;

Expand Down Expand Up @@ -68,3 +70,9 @@ FluidPath::~FluidPath() {
sd_unmount();
}
}

void FluidPath::rehash_fs() {
if (!_isSD) {
HashFS::rehash();
}
}
2 changes: 2 additions & 0 deletions FluidNC/src/FluidPath.h
Original file line number Diff line number Diff line change
Expand Up @@ -26,6 +26,8 @@ class FluidPath : public stdfs::path {
// /localfs/foo -> true, /localfs -> false
bool hasTail() { return ++(++begin()) != end(); }

void rehash_fs();

private:
FluidPath(const char* name, const char* fs, std::error_code*);

Expand Down
2 changes: 1 addition & 1 deletion FluidNC/src/GCode.h
Original file line number Diff line number Diff line change
Expand Up @@ -159,7 +159,7 @@ enum class IoControl : uint8_t {
SetAnalogImmediate = 6, // M68
};

static const int MaxUserDigitalPin = 4;
static const int MaxUserDigitalPin = 8;
static const int MaxUserAnalogPin = 4;

// Modal Group G8: Tool length offset
Expand Down
Loading

0 comments on commit e87fc78

Please sign in to comment.