Merge pull request #686 from thinkl33t/edge
authorArthur Wolf <wolf.arthur@gmail.com>
Sun, 23 Aug 2015 21:44:49 +0000 (23:44 +0200)
committerArthur Wolf <wolf.arthur@gmail.com>
Sun, 23 Aug 2015 21:44:49 +0000 (23:44 +0200)
Changes to laser module PWM config.

39 files changed:
ConfigSamples/AzteegX5Mini.delta/config
ConfigSamples/Smoothieboard/config
ConfigSamples/Snippets/ZprobeGrid.config [new file with mode: 0644]
ConfigSamples/Snippets/drill_cycles.config [new file with mode: 0644]
ConfigSamples/Snippets/filament-change-menu.config [new file with mode: 0644]
FirmwareBin/firmware-disablemsd.bin
FirmwareBin/firmware.bin
FirmwareBin/firmware.bin.md5sum
src/libs/ADC/adc.cpp
src/libs/ADC/adc.h
src/libs/Adc.cpp
src/libs/Adc.h
src/libs/Pwm.h
src/modules/communication/GcodeDispatch.cpp
src/modules/communication/GcodeDispatch.h
src/modules/communication/utils/Gcode.cpp
src/modules/communication/utils/Gcode.h
src/modules/robot/Conveyor.cpp
src/modules/robot/Robot.cpp
src/modules/robot/Robot.h
src/modules/tools/drillingcycles/Drillingcycles.cpp
src/modules/tools/endstops/Endstops.cpp
src/modules/tools/extruder/Extruder.cpp
src/modules/tools/extruder/Extruder.h
src/modules/tools/extruder/ExtruderPublicAccess.h [new file with mode: 0644]
src/modules/tools/scaracal/SCARAcal.cpp
src/modules/tools/spindle/Spindle.cpp
src/modules/tools/switch/Switch.cpp
src/modules/tools/temperaturecontrol/PID_Autotuner.cpp
src/modules/tools/temperaturecontrol/PID_Autotuner.h
src/modules/tools/temperaturecontrol/TemperatureControl.cpp
src/modules/tools/temperaturecontrol/Thermistor.cpp
src/modules/tools/temperaturecontrol/Thermistor.h
src/modules/tools/temperaturecontrol/predefined_thermistors.h
src/modules/tools/toolmanager/ToolManager.cpp
src/modules/tools/zprobe/ZGridStrategy.cpp
src/modules/tools/zprobe/ZProbe.cpp
src/modules/utils/player/Player.cpp
src/modules/utils/simpleshell/SimpleShell.cpp

index d3443e1..720063f 100644 (file)
@@ -97,7 +97,6 @@ temperature_control.hotend.designator        T                #
 temperature_control.bed.enable               false            #
 temperature_control.bed.thermistor_pin       0.23             #
 temperature_control.bed.heater_pin           2.7              #
-temperature_control.bed.beta                 4036             #
 temperature_control.bed.thermistor           EPCOS100K        # http://smoothieware.org/temperaturecontrol#toc5
 #temperature_control.bed.beta                4066             # or set the beta value
 
index 25c5fcb..d952f40 100644 (file)
@@ -316,10 +316,3 @@ network.ip_address                           auto             # use dhcp to get
 #network.ip_mask                              255.255.255.0    # the ip mask
 #network.ip_gateway                           192.168.3.1      # the gateway address
 #network.mac_override                         xx.xx.xx.xx.xx.xx  # override the mac address, only do this if you have a conflict
-
-# Drills module
-# Implement the Canned Drilling Cycles
-# G80-83, G98, G99 in absolute mode only
-# Incremental mode not implemented (L)
-drillingcycles.enable                                false # enable module, default false
-drillingcycles.dwell_units                           S     # dwell units [S = seconds, P = millis], default: S
diff --git a/ConfigSamples/Snippets/ZprobeGrid.config b/ConfigSamples/Snippets/ZprobeGrid.config
new file mode 100644 (file)
index 0000000..45e216b
--- /dev/null
@@ -0,0 +1,27 @@
+leveling-strategy.ZGrid-leveling.enable         true       #
+leveling-strategy.ZGrid-leveling.bed_x          200        # Bed size
+leveling-strategy.ZGrid-leveling.bed_y          200        # Bed Size
+
+# Machine height, used to determine probe attachment point (bed_z / 2)
+leveling-strategy.ZGrid-leveling.bed_z           20
+
+leveling-strategy.ZGrid-leveling.rows           7          # X divisions (Default 5)
+leveling-strategy.ZGrid-leveling.cols           9          # Y divisions (Default 5)
+
+leveling-strategy.ZGrid-leveling.probe_offsets  5,5,16.3   #
+
+#leveling-strategy.ZGrid-leveling.slow_feedrate 100        # optional
+
+#Configure for Machines with bed 0,0 at center of platform
+leveling-strategy.ZGrid-leveling.center_zero      false
+
+# configure for Machines with circular beds
+leveling-strategy.ZGrid-leveling.circular_bed     false
+
+# The machine can be told to wait for probe attachment and confirmation
+leveling-strategy.ZGrid-leveling.wait_for_probe  true
+
+# The machine can be told to home in one of the following modes:
+leveling-strategy.ZGrid-leveling.home_before_probe  homexyz;    #  nohome homexy homexyz (default)
+
+#gamma_max                                    200           # make sure this is set correctly
diff --git a/ConfigSamples/Snippets/drill_cycles.config b/ConfigSamples/Snippets/drill_cycles.config
new file mode 100644 (file)
index 0000000..da5af05
--- /dev/null
@@ -0,0 +1,6 @@
+# Drills module
+# Implement the Canned Drilling Cycles
+# G80-83, G98, G99 in absolute mode only
+# Incremental mode not implemented (L)
+drillingcycles.enable                                false # enable module, default false
+drillingcycles.dwell_units                           S     # dwell units [S = seconds, P = millis], default: S
diff --git a/ConfigSamples/Snippets/filament-change-menu.config b/ConfigSamples/Snippets/filament-change-menu.config
new file mode 100644 (file)
index 0000000..8064eb3
--- /dev/null
@@ -0,0 +1,10 @@
+custom_menu.filament_change.enable                true              #
+custom_menu.filament_change.name                  filament_change          #
+custom_menu.filament_change.command               M600               #
+
+custom_menu.resume.enable                true              #
+custom_menu.resume.name                  resume          #
+custom_menu.resume.command               M601               #
+
+after_suspend_gcode  G91_G0Z10_G90  # optionally raise nozzle 10mm after suspend
+leave_heaters_on_suspend  true   # set to false if you want the heaters turned off on suspend
index b2a8d77..4dc3cd5 100755 (executable)
Binary files a/FirmwareBin/firmware-disablemsd.bin and b/FirmwareBin/firmware-disablemsd.bin differ
index 07f41f9..0e4fef4 100755 (executable)
Binary files a/FirmwareBin/firmware.bin and b/FirmwareBin/firmware.bin differ
index 0c9b5b0..1786633 100644 (file)
@@ -1 +1 @@
-7b86e9d1e0aa2f4d6fa09ed03c2dfeda  FirmwareBin/firmware.bin
+073e16c3a2b768d91e8ea8a675c5a532  FirmwareBin/firmware.bin
index a6fc701..945b5d1 100644 (file)
@@ -4,15 +4,16 @@
  */
 #include "mbed.h"
 #include "adc.h"
-\r
-\r
+
+using namespace mbed;
+
 ADC *ADC::instance;
-\r
+
 ADC::ADC(int sample_rate, int cclk_div)
     {
-\r
+
     int i, adc_clk_freq, pclk, clock_div, max_div=1;
-\r
+
     //Work out CCLK
     adc_clk_freq=CLKS_PER_SAMPLE*sample_rate;
     int m = (LPC_SC->PLL0CFG & 0xFFFF) + 1;
@@ -20,7 +21,7 @@ ADC::ADC(int sample_rate, int cclk_div)
     int cclkdiv = LPC_SC->CCLKCFG + 1;
     int Fcco = (2 * m * XTAL_FREQ) / n;
     int cclk = Fcco / cclkdiv;
-\r
+
     //Power up the ADC
     LPC_SC->PCONP |= (1 << 12);
     //Set clock at cclk / 1.
@@ -39,7 +40,7 @@ ADC::ADC(int sample_rate, int cclk_div)
             LPC_SC->PCLKSEL0 |= 0x3 << 24;
             break;
         default:
-            printf("Warning: ADC CCLK clock divider must be 1, 2, 4 or 8. %u supplied.\n",
+            printf("ADC Warning: ADC CCLK clock divider must be 1, 2, 4 or 8. %u supplied.\n",
                 cclk_div);
             printf("Defaulting to 1.\n");
             LPC_SC->PCLKSEL0 |= 0x1 << 24;
@@ -47,29 +48,28 @@ ADC::ADC(int sample_rate, int cclk_div)
     }
     pclk = cclk / cclk_div;
     clock_div=pclk / adc_clk_freq;
-\r
+
     if (clock_div > 0xFF) {
-        //printf("Warning: Clock division is %u which is above 255 limit. Re-Setting at limit.\n",
-        //    clock_div);
+        printf("ADC Warning: Clock division is %u which is above 255 limit. Re-Setting at limit.\n", clock_div);
         clock_div=0xFF;
     }
     if (clock_div == 0) {
-        printf("Warning: Clock division is 0. Re-Setting to 1.\n");
+        printf("ADC Warning: Clock division is 0. Re-Setting to 1.\n");
         clock_div=1;
     }
-\r
+
     _adc_clk_freq=pclk / clock_div;
     if (_adc_clk_freq > MAX_ADC_CLOCK) {
-        printf("Warning: Actual ADC sample rate of %u which is above %u limit\n",
+        printf("ADC Warning: Actual ADC sample rate of %u which is above %u limit\n",
             _adc_clk_freq / CLKS_PER_SAMPLE, MAX_ADC_CLOCK / CLKS_PER_SAMPLE);
         while ((pclk / max_div) > MAX_ADC_CLOCK) max_div++;
-        printf("Maximum recommended sample rate is %u\n", (pclk / max_div) / CLKS_PER_SAMPLE);
+        printf("ADC Warning: Maximum recommended sample rate is %u\n", (pclk / max_div) / CLKS_PER_SAMPLE);
     }
-\r
+
     LPC_ADC->ADCR =
         ((clock_div - 1 ) << 8 ) |    //Clkdiv
         ( 1 << 21 );                  //A/D operational
-\r
+
     //Default no channels enabled
     LPC_ADC->ADCR &= ~0xFF;
     //Default NULL global custom isr
@@ -79,28 +79,28 @@ ADC::ADC(int sample_rate, int cclk_div)
         _adc_data[i] = 0;
         _adc_isr[i] = NULL;
     }
-\r
-\r
+
+
     //* Attach IRQ
     instance = this;
     NVIC_SetVector(ADC_IRQn, (uint32_t)&_adcisr);
-\r
+
     //Disable global interrupt
     LPC_ADC->ADINTEN &= ~0x100;
-\r
+
 };
-\r
+
 void ADC::_adcisr(void)
 {
     instance->adcisr();
 }
-\r
-\r
+
+
 void ADC::adcisr(void)
 {
     uint32_t stat;
     int chan;
-\r
+
     // Read status
     stat = LPC_ADC->ADSTAT;
     //Scan channels for over-run or done and update array
@@ -112,7 +112,7 @@ void ADC::adcisr(void)
     if (stat & 0x2020) _adc_data[5] = LPC_ADC->ADDR5;
     if (stat & 0x4040) _adc_data[6] = LPC_ADC->ADDR6;
     if (stat & 0x8080) _adc_data[7] = LPC_ADC->ADDR7;
-\r
+
     // Channel that triggered interrupt
     chan = (LPC_ADC->ADGDR >> 24) & 0x07;
     //User defined interrupt handlers
@@ -122,7 +122,7 @@ void ADC::adcisr(void)
         _adc_g_isr(chan, _adc_data[chan]);
     return;
 }
-\r
+
 int ADC::_pin_to_channel(PinName pin) {
     int chan;
     switch (pin) {
@@ -148,25 +148,25 @@ int ADC::_pin_to_channel(PinName pin) {
     }
     return(chan);
 }
-\r
+
 PinName ADC::channel_to_pin(int chan) {
     const PinName pin[8]={p15, p16, p17, p18, p19, p20, p15, p15};
-    \r
+
     if ((chan < 0) || (chan > 5))
         fprintf(stderr, "ADC channel %u is outside range available to MBED pins.\n", chan);
     return(pin[chan & 0x07]);
 }
-\r
-\r
+
+
 int ADC::channel_to_pin_number(int chan) {
     const int pin[8]={15, 16, 17, 18, 19, 20, 0, 0};
-    \r
+
     if ((chan < 0) || (chan > 5))
         fprintf(stderr, "ADC channel %u is outside range available to MBED pins.\n", chan);
     return(pin[chan & 0x07]);
 }
-\r
-\r
+
+
 uint32_t ADC::_data_of_pin(PinName pin) {
     //If in burst mode and at least one interrupt enabled then
     //take all values from _adc_data
@@ -191,7 +191,7 @@ uint32_t ADC::_data_of_pin(PinName pin) {
         }
     }
 }
-\r
+
 //Enable or disable an ADC pin
 void ADC::setup(PinName pin, int state) {
     int chan;
@@ -275,27 +275,27 @@ void ADC::setup(PinName pin, int state) {
 //Return channel enabled/disabled state
 int ADC::setup(PinName pin) {
     int chan;
-    \r
+
     chan = _pin_to_channel(pin);
     return((LPC_ADC->ADCR & (1 << chan)) >> chan);
 }
-\r
+
 //Select channel already setup
 void ADC::select(PinName pin) {
     int chan;
-    \r
+
     //Only one channel can be selected at a time if not in burst mode
     if (!burst()) LPC_ADC->ADCR &= ~0xFF;
     //Select channel
     chan = _pin_to_channel(pin);
     LPC_ADC->ADCR |= (1 << chan);
 }
-\r
+
 //Enable or disable burst mode
 void ADC::burst(int state) {
     if ((state & 1) == 1) {
         if (startmode(0) != 0)
-            fprintf(stderr, "Warning. startmode is %u. Must be 0 for burst mode.\n", startmode(0));
+            fprintf(stderr, "ADC Warning. startmode is %u. Must be 0 for burst mode.\n", startmode(0));
         LPC_ADC->ADCR |= (1 << 16);
     }
     else
@@ -305,18 +305,18 @@ void ADC::burst(int state) {
 int  ADC::burst(void) {
     return((LPC_ADC->ADCR & (1 << 16)) >> 16);
 }
-\r
+
 //Set startmode and edge
 void ADC::startmode(int mode, int edge) {
     int lpc_adc_temp;
-    \r
+
     //Reset start mode and edge bit,
     lpc_adc_temp = LPC_ADC->ADCR & ~(0x0F << 24);
     //Write with new values
     lpc_adc_temp |= ((mode & 7) << 24) | ((edge & 1) << 27);
     LPC_ADC->ADCR = lpc_adc_temp;
 }
-\r
+
 //Return startmode state according to mode_edge=0: mode and mode_edge=1: edge
 int ADC::startmode(int mode_edge){
     switch (mode_edge) {
@@ -327,17 +327,17 @@ int ADC::startmode(int mode_edge){
             return((LPC_ADC->ADCR >> 27) & 0x01);
     }
 }
-\r
+
 //Start ADC conversion
 void ADC::start(void) {
     startmode(1,0);
 }
-\r
-\r
+
+
 //Set interrupt enable/disable for pin to state
 void ADC::interrupt_state(PinName pin, int state) {
     int chan;
-    \r
+
     chan = _pin_to_channel(pin);
     if (state == 1) {
         LPC_ADC->ADINTEN &= ~0x100;
@@ -351,67 +351,67 @@ void ADC::interrupt_state(PinName pin, int state) {
             NVIC_DisableIRQ(ADC_IRQn);
     }
 }
-\r
+
 //Return enable/disable state of interrupt for pin
 int ADC::interrupt_state(PinName pin) {
     int chan;
-        \r
+
     chan = _pin_to_channel(pin);
     return((LPC_ADC->ADINTEN >> chan) & 0x01);
 }
-\r
-\r
+
+
 //Attach custom interrupt handler replacing default
 void ADC::attach(void(*fptr)(void)) {
     //* Attach IRQ
     NVIC_SetVector(ADC_IRQn, (uint32_t)fptr);
 }
-\r
+
 //Restore default interrupt handler
 void ADC::detach(void) {
     //* Attach IRQ
     instance = this;
     NVIC_SetVector(ADC_IRQn, (uint32_t)&_adcisr);
 }
-\r
-\r
+
+
 //Append interrupt handler for pin to function isr
 void ADC::append(PinName pin, void(*fptr)(uint32_t value)) {
     int chan;
-        \r
+
     chan = _pin_to_channel(pin);
     _adc_isr[chan] = fptr;
 }
-\r
+
 //Append interrupt handler for pin to function isr
 void ADC::unappend(PinName pin) {
     int chan;
-        \r
+
     chan = _pin_to_channel(pin);
     _adc_isr[chan] = NULL;
 }
-\r
+
 //Unappend global interrupt handler to function isr
 void ADC::append(void(*fptr)(int chan, uint32_t value)) {
     _adc_g_isr = fptr;
 }
-\r
+
 //Detach global interrupt handler to function isr
 void ADC::unappend() {
     _adc_g_isr = NULL;
 }
-\r
+
 //Set ADC offset
-void offset(int offset) {
+void ADC::offset(int offset) {
     LPC_ADC->ADTRM &= ~(0x07 << 4);
     LPC_ADC->ADTRM |= (offset & 0x07) << 4;
 }
-\r
+
 //Return current ADC offset
-int offset(void) {
+int ADC::offset(void) {
     return((LPC_ADC->ADTRM >> 4) & 0x07);
 }
-\r
+
 //Return value of ADC on pin
 int ADC::read(PinName pin) {
     //Reset DONE and OVERRUN flags of interrupt handled ADC data
@@ -419,21 +419,21 @@ int ADC::read(PinName pin) {
     //Return value
     return((_data_of_pin(pin) >> 4) & 0xFFF);
 }
-\r
+
 //Return DONE flag of ADC on pin
 int ADC::done(PinName pin) {
     return((_data_of_pin(pin) >> 31) & 0x01);
 }
-\r
+
 //Return OVERRUN flag of ADC on pin
 int ADC::overrun(PinName pin) {
     return((_data_of_pin(pin) >> 30) & 0x01);
 }
-\r
+
 int ADC::actual_adc_clock(void) {
     return(_adc_clk_freq);
 }
-\r
+
 int ADC::actual_sample_rate(void) {
     return(_adc_clk_freq / CLKS_PER_SAMPLE);
 }
index 9ff7248..fbc7255 100644 (file)
@@ -2,39 +2,40 @@
  * Copyright (c) 2010, sblandford
  * released under MIT license http://mbed.org/licence/mit
  */
-\r
+
 #ifndef MBED_ADC_H
 #define MBED_ADC_H
\r
+
 #include "PinNames.h" // mbed.h lib
 #define XTAL_FREQ       12000000
 #define MAX_ADC_CLOCK   13000000
 #define CLKS_PER_SAMPLE 64
-\r
+
+namespace mbed {
 class ADC {
 public:
-\r
+
     //Initialize ADC with ADC maximum sample rate of
     //sample_rate and system clock divider of cclk_div
     //Maximum recommened sample rate is 184000
     ADC(int sample_rate, int cclk_div);
-\r
+
     //Enable/disable ADC on pin according to state
     //and also select/de-select for next conversion
     void setup(PinName pin, int state);
-\r
+
     //Return enabled/disabled state of ADC on pin
     int setup(PinName pin);
-\r
+
     //Enable/disable burst mode according to state
     void burst(int state);
-\r
+
     //Select channel already setup
     void select(PinName pin);
-\r
+
     //Return burst mode enabled/disabled
     int burst(void);
-\r
+
     /*Set start condition and edge according to mode:
     0 - No start (this value should be used when clearing PDN to 0).
     1 - Start conversion now.
@@ -54,78 +55,79 @@ public:
     1 - Falling edge
     */
     void startmode(int mode, int edge);
-    \r
+
     //Return startmode state according to mode_edge=0: mode and mode_edge=1: edge
     int startmode(int mode_edge);
-    \r
+
     //Start ADC conversion
     void start(void);
-\r
+
     //Set interrupt enable/disable for pin to state
     void interrupt_state(PinName pin, int state);
-    \r
+
     //Return enable/disable state of interrupt for pin
     int interrupt_state(PinName pin);
-\r
+
     //Attach custom interrupt handler replacing default
     void attach(void(*fptr)(void));
-\r
+
     //Restore default interrupt handler
     void detach(void);
-\r
+
     //Append custom interrupt handler for pin
     void append(PinName pin, void(*fptr)(uint32_t value));
-\r
+
     //Unappend custom interrupt handler for pin
     void unappend(PinName pin);
-\r
+
     //Append custom global interrupt handler
     void append(void(*fptr)(int chan, uint32_t value));
-\r
+
     //Unappend custom global interrupt handler
     void unappend(void);
-\r
+
     //Set ADC offset to a value 0-7
     void offset(int offset);
-    \r
+
     //Return current ADC offset
     int offset(void);
-\r
+
     //Return value of ADC on pin
     int read(PinName pin);
-\r
+
     //Return DONE flag of ADC on pin
     int done(PinName pin);
-    \r
+
     //Return OVERRUN flag of ADC on pin
     int overrun(PinName pin);
-\r
+
     //Return actual ADC clock
     int actual_adc_clock(void);
-    \r
+
     //Return actual maximum sample rate
     int actual_sample_rate(void);
-\r
+
     //Return pin ID of ADC channel
     PinName channel_to_pin(int chan);
-\r
+
     //Return pin number of ADC channel
     int channel_to_pin_number(int chan);
-\r
-\r
-private:
+
     int _pin_to_channel(PinName pin);
+
+private:
     uint32_t _data_of_pin(PinName pin);
-\r
+
     int _adc_clk_freq;
     void adcisr(void);
     static void _adcisr(void);
     static ADC *instance;
-    \r
+
     uint32_t _adc_data[8];
     void(*_adc_isr[8])(uint32_t value);
     void(*_adc_g_isr)(int chan, uint32_t value);
     void(*_adc_m_isr)(void);
 };
-\r
+}
+
 #endif
index 568449e..c85d38c 100644 (file)
 #include "libs/Pin.h"
 #include "libs/ADC/adc.h"
 #include "libs/Pin.h"
+#include "libs/Median.h"
 
+#include <cstring>
+#include <algorithm>
+
+#include "mbed.h"
 
-using namespace std;
-#include <vector>
 // This is an interface to the mbed.org ADC library you can find in libs/ADC/adc.h
 // TODO : Having the same name is confusing, should change that
 
-Adc::Adc(){
-    this->adc = new ADC(1000, 1);
+Adc *Adc::instance;
+
+static void sample_isr(int chan, uint32_t value)
+{
+    Adc::instance->new_sample(chan, value);
 }
 
+Adc::Adc()
+{
+    instance = this;
+    // ADC sample rate need to be fast enough to be able to read the enabled channels within the thermistor poll time
+    // even though ther maybe 32 samples we only need one new one within the polling time
+    const uint32_t sample_rate= 1000; // 1KHz sample rate
+    this->adc = new mbed::ADC(sample_rate, 8);
+    this->adc->append(sample_isr);
+}
+
+/*
+LPC176x ADC channels and pins
+
+Adc Channel Port Pin    Pin Functions                       Associated PINSEL Register
+AD0 P0.23   0-GPIO,     1-AD0[0], 2-I2SRX_CLK, 3-CAP3[0]    14,15 bits of PINSEL1
+AD1 P0.24   0-GPIO,     1-AD0[1], 2-I2SRX_WS, 3-CAP3[1]     16,17 bits of PINSEL1
+AD2 P0.25   0-GPIO,     1-AD0[2], 2-I2SRX_SDA, 3-TXD3       18,19 bits of PINSEL1
+AD3 P0.26   0-GPIO,     1-AD0[3], 2-AOUT, 3-RXD3            20,21 bits of PINSEL1
+AD4 P1.30   0-GPIO,     1-VBUS, 2- , 3-AD0[4]               28,29 bits of PINSEL3
+AD5 P1.31   0-GPIO,     1-SCK1, 2- , 3-AD0[5]               30,31 bits of PINSEL3
+AD6 P0.3    0-GPIO,     1-RXD0, 2-AD0[6], 3-                6,7 bits of PINSEL0
+AD7 P0.2    0-GPIO,     1-TXD0, 2-AD0[7], 3-                4,5 bits of PINSEL0
+*/
+
 // Enables ADC on a given pin
-void Adc::enable_pin(Pin* pin){
+void Adc::enable_pin(Pin *pin)
+{
     PinName pin_name = this->_pin_to_pinname(pin);
+    int channel = adc->_pin_to_channel(pin_name);
+    memset(sample_buffers[channel], 0, sizeof(sample_buffers[0]));
+
     this->adc->burst(1);
-    this->adc->setup(pin_name,1);
-    this->adc->interrupt_state(pin_name,1);
+    this->adc->setup(pin_name, 1);
+    this->adc->interrupt_state(pin_name, 1);
 }
 
-// Read the last value ( burst mode ) on a given pin
-unsigned int Adc::read(Pin* pin){
-    return this->adc->read(this->_pin_to_pinname(pin));
+// Keeps the last 8 values for each channel
+// This is called in an ISR, so sample_buffers needs to be accessed atomically
+void Adc::new_sample(int chan, uint32_t value)
+{
+    // Shuffle down and add new value to the end
+    if(chan < num_channels) {
+        memmove(&sample_buffers[chan][0], &sample_buffers[chan][1], sizeof(sample_buffers[0]) - sizeof(sample_buffers[0][0]));
+        sample_buffers[chan][num_samples - 1] = (value >> 4) & 0xFFF; // the 12 bit ADC reading
+    }
+}
+
+//#define USE_MEDIAN_FILTER
+// Read the filtered value ( burst mode ) on a given pin
+unsigned int Adc::read(Pin *pin)
+{
+    PinName p = this->_pin_to_pinname(pin);
+    int channel = adc->_pin_to_channel(p);
+
+    uint16_t median_buffer[num_samples];
+    // needs atomic access TODO maybe be able to use std::atomic here or some lockless mutex
+    __disable_irq();
+    memcpy(median_buffer, sample_buffers[channel], sizeof(median_buffer));
+    __enable_irq();
+
+#ifdef USE_MEDIAN_FILTER
+    // returns the median value of the last 8 samples
+    return median_buffer[quick_median(median_buffer, num_samples)];
+
+#elif defined(OVERSAMPLE)
+    // Oversample to get 2 extra bits of resolution
+    // weed out top and bottom worst values then oversample the rest
+    // put into a 4 element moving average and return the average of the last 4 oversampled readings
+    static uint16_t ave_buf[num_channels][4] =  { {0} };
+    std::sort(median_buffer, median_buffer + num_samples);
+    uint32_t sum = 0;
+    for (int i = num_samples / 4; i < (num_samples - (num_samples / 4)); ++i) {
+        sum += median_buffer[i];
+    }
+    // this slows down the rate of change a little bit
+    ave_buf[channel][3]= ave_buf[channel][2];
+    ave_buf[channel][2]= ave_buf[channel][1];
+    ave_buf[channel][1]= ave_buf[channel][0];
+    ave_buf[channel][0]= sum >> OVERSAMPLE;
+    return roundf((ave_buf[channel][0]+ave_buf[channel][1]+ave_buf[channel][2]+ave_buf[channel][3])/4.0F);
+
+#else
+    // sort the 8 readings and return the average of the middle 4
+    std::sort(median_buffer, median_buffer + num_samples);
+    int sum = 0;
+    for (int i = num_samples / 4; i < (num_samples - (num_samples / 4)); ++i) {
+        sum += median_buffer[i];
+    }
+    return sum / (num_samples / 2);
+
+#endif
 }
 
 // Convert a smoothie Pin into a mBed Pin
-PinName Adc::_pin_to_pinname(Pin* pin){
-    if( pin->port == LPC_GPIO0 && pin->pin == 23 ){
+PinName Adc::_pin_to_pinname(Pin *pin)
+{
+    if( pin->port == LPC_GPIO0 && pin->pin == 23 ) {
         return p15;
-    }else if( pin->port == LPC_GPIO0 && pin->pin == 24 ){
+    } else if( pin->port == LPC_GPIO0 && pin->pin == 24 ) {
         return p16;
-    }else if( pin->port == LPC_GPIO0 && pin->pin == 25 ){
+    } else if( pin->port == LPC_GPIO0 && pin->pin == 25 ) {
         return p17;
-    }else if( pin->port == LPC_GPIO0 && pin->pin == 26 ){
+    } else if( pin->port == LPC_GPIO0 && pin->pin == 26 ) {
         return p18;
-    }else if( pin->port == LPC_GPIO1 && pin->pin == 30 ){
+    } else if( pin->port == LPC_GPIO1 && pin->pin == 30 ) {
         return p19;
-    }else if( pin->port == LPC_GPIO1 && pin->pin == 31 ){
+    } else if( pin->port == LPC_GPIO1 && pin->pin == 31 ) {
         return p20;
-    }else{
+    } else {
         //TODO: Error
         return NC;
     }
index 4b30924..163d0a8 100644 (file)
 #define ADC_H
 
 #include "PinNames.h" // mbed.h lib
-#include "libs/ADC/adc.h"
+
+#include <cmath>
 
 class Pin;
+namespace mbed {
+    class ADC;
+}
+
+// define how many bits of extra resolution required
+// 2 bits means the 12bit ADC is 14 bits of resolution
+#define OVERSAMPLE 2
+
+class Adc
+{
+public:
+    Adc();
+    void enable_pin(Pin *pin);
+    unsigned int read(Pin *pin);
+
+    static Adc *instance;
+    void new_sample(int chan, uint32_t value);
+    // return the maximum ADC value, base is 12bits 4095.
+#ifdef OVERSAMPLE
+    int get_max_value() const { return 4095 << OVERSAMPLE;}
+#else
+    int get_max_value() const { return 4095;}
+#endif
 
-class Adc {
-    public:
-        Adc();
-        void enable_pin(Pin* pin);
-        unsigned int read(Pin* pin);
-        PinName _pin_to_pinname(Pin* pin);
+private:
+    PinName _pin_to_pinname(Pin *pin);
+    mbed::ADC *adc;
 
-        ADC* adc;
+    static const int num_channels= 6;
+#ifdef OVERSAMPLE
+    // we need 4^n sample to oversample and we get double that to filter out spikes
+    static const int num_samples= powf(4, OVERSAMPLE)*2;
+#else
+    static const int num_samples= 8;
+#endif
+    // buffers storing the last num_samples readings for each channel
+    uint16_t sample_buffers[num_channels][num_samples];
 };
 
-
-
 #endif
index 649fc58..559194b 100644 (file)
@@ -17,6 +17,7 @@ public:
     int      max_pwm(void);
 
     void     pwm(int);
+    int      get_pwm() const { return _pwm; }
     void     set(bool);
 
 private:
index 1c7d9e2..523918a 100644 (file)
@@ -47,7 +47,6 @@ GcodeDispatch::GcodeDispatch()
 // Called when the module has just been loaded
 void GcodeDispatch::on_module_loaded()
 {
-    return_error_on_unhandled_gcode = THEKERNEL->config->value( return_error_on_unhandled_gcode_checksum )->by_default(false)->as_bool();
     this->register_for_event(ON_CONSOLE_LINE_RECEIVED);
     this->register_for_event(ON_HALT);
 }
@@ -235,9 +234,7 @@ try_again:
                     if(gcode->add_nl)
                         new_message.stream->printf("\r\n");
 
-                    if( return_error_on_unhandled_gcode == true && gcode->accepted_by_module == false)
-                        new_message.stream->printf("ok (command unclaimed)\r\n");
-                    else if(!gcode->txt_after_ok.empty()) {
+                    if(!gcode->txt_after_ok.empty()) {
                         new_message.stream->printf("ok %s\r\n", gcode->txt_after_ok.c_str());
                         gcode->txt_after_ok.clear();
                     } else
index c444f69..18c356d 100644 (file)
@@ -31,7 +31,6 @@ private:
     struct {
         bool uploading: 1;
         bool halted: 1;
-        bool return_error_on_unhandled_gcode:1;
     };
 };
 
index 7823b9d..2d3d83b 100644 (file)
@@ -22,7 +22,6 @@ Gcode::Gcode(const string &command, StreamOutput *stream, bool strip)
     this->add_nl= false;
     this->stream= stream;
     this->millimeters_of_travel = 0.0F;
-    this->accepted_by_module = false;
     prepare_cached_values(strip);
     this->stripped= strip;
 }
@@ -45,7 +44,6 @@ Gcode::Gcode(const Gcode &to_copy)
     this->g                     = to_copy.g;
     this->add_nl                = to_copy.add_nl;
     this->stream                = to_copy.stream;
-    this->accepted_by_module    = false;
     this->txt_after_ok.assign( to_copy.txt_after_ok );
 }
 
@@ -62,7 +60,6 @@ Gcode &Gcode::operator= (const Gcode &to_copy)
         this->stream                = to_copy.stream;
         this->txt_after_ok.assign( to_copy.txt_after_ok );
     }
-    this->accepted_by_module = false;
     return *this;
 }
 
@@ -182,11 +179,6 @@ void Gcode::prepare_cached_values(bool strip)
     }
 }
 
-void Gcode::mark_as_taken()
-{
-    this->accepted_by_module = true;
-}
-
 // strip off X Y Z I J K parameters if G0/1/2/3
 void Gcode::strip_parameters()
 {
index 21c935d..b6ee8d8 100644 (file)
@@ -30,7 +30,6 @@ class Gcode {
         uint32_t get_uint ( char letter, char **ptr= nullptr ) const;
         int get_num_args() const;
         std::map<char,float> get_args() const;
-        void mark_as_taken();
         void strip_parameters();
 
         // FIXME these should be private
@@ -42,7 +41,6 @@ class Gcode {
             bool add_nl:1;
             bool has_m:1;
             bool has_g:1;
-            bool accepted_by_module:1;
             bool stripped:1;
         };
 
index 25922b1..f8b6873 100644 (file)
@@ -136,7 +136,6 @@ void Conveyor::on_config_reload(void* argument)
 
 void Conveyor::append_gcode(Gcode* gcode)
 {
-    gcode->mark_as_taken();
     queue.head_ref()->append_gcode(gcode);
 }
 
index e4bc861..2ecf357 100644 (file)
@@ -22,6 +22,7 @@ using std::string;
 #include "StepperMotor.h"
 #include "Gcode.h"
 #include "PublicDataRequest.h"
+#include "PublicData.h"
 #include "RobotPublicAccess.h"
 #include "arm_solutions/BaseSolution.h"
 #include "arm_solutions/CartesianSolution.h"
@@ -36,6 +37,7 @@ using std::string;
 #include "ConfigValue.h"
 #include "libs/StreamOutput.h"
 #include "StreamOutputPool.h"
+#include "ExtruderPublicAccess.h"
 
 #define  default_seek_rate_checksum          CHECKSUM("default_seek_rate")
 #define  default_feed_rate_checksum          CHECKSUM("default_feed_rate")
@@ -94,7 +96,6 @@ using std::string;
 #define  beta_checksum                       CHECKSUM("beta")
 #define  gamma_checksum                      CHECKSUM("gamma")
 
-
 #define NEXT_ACTION_DEFAULT 0
 #define NEXT_ACTION_DWELL 1
 #define NEXT_ACTION_GO_HOME 2
@@ -341,10 +342,10 @@ void Robot::on_gcode_received(void *argument)
     //G-letter Gcodes are mostly what the Robot module is interrested in, other modules also catch the gcode event and do stuff accordingly
     if( gcode->has_g) {
         switch( gcode->g ) {
-            case 0:  this->motion_mode = MOTION_MODE_SEEK; gcode->mark_as_taken(); break;
-            case 1:  this->motion_mode = MOTION_MODE_LINEAR; gcode->mark_as_taken();  break;
-            case 2:  this->motion_mode = MOTION_MODE_CW_ARC; gcode->mark_as_taken();  break;
-            case 3:  this->motion_mode = MOTION_MODE_CCW_ARC; gcode->mark_as_taken();  break;
+            case 0:  this->motion_mode = MOTION_MODE_SEEK;  break;
+            case 1:  this->motion_mode = MOTION_MODE_LINEAR;   break;
+            case 2:  this->motion_mode = MOTION_MODE_CW_ARC;   break;
+            case 3:  this->motion_mode = MOTION_MODE_CCW_ARC;   break;
             case 4: {
                 uint32_t delay_ms= 0;
                 if (gcode->has_letter('P')) {
@@ -362,16 +363,15 @@ void Robot::on_gcode_received(void *argument)
                         THEKERNEL->call_event(ON_IDLE, this);
                     }
                 }
-                gcode->mark_as_taken();
-            } 
+            }
             break;
-            case 17: this->select_plane(X_AXIS, Y_AXIS, Z_AXIS); gcode->mark_as_taken();  break;
-            case 18: this->select_plane(X_AXIS, Z_AXIS, Y_AXIS); gcode->mark_as_taken();  break;
-            case 19: this->select_plane(Y_AXIS, Z_AXIS, X_AXIS); gcode->mark_as_taken();  break;
-            case 20: this->inch_mode = true; gcode->mark_as_taken();  break;
-            case 21: this->inch_mode = false; gcode->mark_as_taken();  break;
-            case 90: this->absolute_mode = true; gcode->mark_as_taken();  break;
-            case 91: this->absolute_mode = false; gcode->mark_as_taken();  break;
+            case 17: this->select_plane(X_AXIS, Y_AXIS, Z_AXIS);   break;
+            case 18: this->select_plane(X_AXIS, Z_AXIS, Y_AXIS);   break;
+            case 19: this->select_plane(Y_AXIS, Z_AXIS, X_AXIS);   break;
+            case 20: this->inch_mode = true;   break;
+            case 21: this->inch_mode = false;   break;
+            case 90: this->absolute_mode = true;   break;
+            case 91: this->absolute_mode = false;   break;
             case 92: {
                 if(gcode->get_num_args() == 0) {
                     for (int i = X_AXIS; i <= Z_AXIS; ++i) {
@@ -385,8 +385,6 @@ void Robot::on_gcode_received(void *argument)
                         }
                     }
                 }
-
-                gcode->mark_as_taken();
                 return;
             }
         }
@@ -404,7 +402,6 @@ void Robot::on_gcode_received(void *argument)
 
                 gcode->stream->printf("X:%g Y:%g Z:%g F:%g ", actuators[0]->steps_per_mm, actuators[1]->steps_per_mm, actuators[2]->steps_per_mm, seconds_per_minute);
                 gcode->add_nl = true;
-                gcode->mark_as_taken();
                 check_max_actuator_speeds();
                 return;
 
@@ -418,12 +415,10 @@ void Robot::on_gcode_received(void *argument)
                                  actuators[Y_AXIS]->get_current_position(),
                                  actuators[Z_AXIS]->get_current_position() );
                 gcode->txt_after_ok.append(buf, n);
-                gcode->mark_as_taken();
             }
             return;
 
             case 120: { // push state
-                gcode->mark_as_taken();
                 bool b= this->absolute_mode;
                 saved_state_t s(this->feed_rate, this->seek_rate, b);
                 state_stack.push(s);
@@ -431,7 +426,6 @@ void Robot::on_gcode_received(void *argument)
             break;
 
             case 121: // pop state
-                gcode->mark_as_taken();
                 if(!state_stack.empty()) {
                     auto s= state_stack.top();
                     state_stack.pop();
@@ -457,16 +451,16 @@ void Robot::on_gcode_received(void *argument)
 
                 check_max_actuator_speeds();
 
-                gcode->stream->printf("X:%g Y:%g Z:%g  A:%g B:%g C:%g ",
-                                      this->max_speeds[X_AXIS], this->max_speeds[Y_AXIS], this->max_speeds[Z_AXIS],
-                                      alpha_stepper_motor->get_max_rate(), beta_stepper_motor->get_max_rate(), gamma_stepper_motor->get_max_rate());
-                gcode->add_nl = true;
-                gcode->mark_as_taken();
+                if(gcode->get_num_args() == 0) {
+                    gcode->stream->printf("X:%g Y:%g Z:%g  A:%g B:%g C:%g ",
+                                          this->max_speeds[X_AXIS], this->max_speeds[Y_AXIS], this->max_speeds[Z_AXIS],
+                                          alpha_stepper_motor->get_max_rate(), beta_stepper_motor->get_max_rate(), gamma_stepper_motor->get_max_rate());
+                    gcode->add_nl = true;
+                }
+
                 break;
 
             case 204: // M204 Snnn - set acceleration to nnn, Znnn sets z acceleration
-                gcode->mark_as_taken();
-
                 if (gcode->has_letter('S')) {
                     float acc = gcode->get_value('S'); // mm/s^2
                     // enforce minimum
@@ -484,7 +478,6 @@ void Robot::on_gcode_received(void *argument)
                 break;
 
             case 205: // M205 Xnnn - set junction deviation, Z - set Z junction deviation, Snnn - Set minimum planner speed, Ynnn - set minimum step rate
-                gcode->mark_as_taken();
                 if (gcode->has_letter('X')) {
                     float jd = gcode->get_value('X');
                     // enforce minimum
@@ -512,7 +505,6 @@ void Robot::on_gcode_received(void *argument)
                 break;
 
             case 220: // M220 - speed override percentage
-                gcode->mark_as_taken();
                 if (gcode->has_letter('S')) {
                     float factor = gcode->get_value('S');
                     // enforce minimum 10% speed
@@ -523,11 +515,12 @@ void Robot::on_gcode_received(void *argument)
                         factor = 1000.0F;
 
                     seconds_per_minute = 6000.0F / factor;
+                }else{
+                    gcode->stream->printf("Speed factor at %6.2f %%\n", 6000.0F / seconds_per_minute);
                 }
                 break;
 
             case 400: // wait until all moves are done up to this point
-                gcode->mark_as_taken();
                 THEKERNEL->conveyor->wait_for_empty_queue();
                 break;
 
@@ -549,12 +542,11 @@ void Robot::on_gcode_received(void *argument)
                     }
                     gcode->stream->printf("\n");
                 }
-                gcode->mark_as_taken();
+
                 break;
             }
 
             case 665: { // M665 set optional arm solution variables based on arm solution.
-                gcode->mark_as_taken();
                 // the parameter args could be any letter each arm solution only accepts certain ones
                 BaseSolution::arm_options_t options= gcode->get_args();
                 options.erase('S'); // don't include the S
@@ -680,7 +672,7 @@ void Robot::reset_position_from_current_actuator_position()
 }
 
 // Convert target from millimeters to steps, and append this to the planner
-void Robot::append_milestone( float target[], float rate_mm_s )
+void Robot::append_milestone(Gcode *gcode, float target[], float rate_mm_s )
 {
     float deltas[3];
     float unit_vec[3];
@@ -724,12 +716,28 @@ void Robot::append_milestone( float target[], float rate_mm_s )
     // find actuator position given cartesian position, use actual adjusted target
     arm_solution->cartesian_to_actuator( transformed_target, actuator_pos );
 
+    float isecs= rate_mm_s / millimeters_of_travel;
     // check per-actuator speed limits
     for (int actuator = 0; actuator <= 2; actuator++) {
-        float actuator_rate  = fabs(actuator_pos[actuator] - actuators[actuator]->last_milestone_mm) * rate_mm_s / millimeters_of_travel;
-
-        if (actuator_rate > actuators[actuator]->get_max_rate())
+        float actuator_rate  = fabsf(actuator_pos[actuator] - actuators[actuator]->last_milestone_mm) * isecs;
+        if (actuator_rate > actuators[actuator]->get_max_rate()){
             rate_mm_s *= (actuators[actuator]->get_max_rate() / actuator_rate);
+        }
+    }
+
+    // if we have volumetric limits enabled we calculate the volume for this move and limit the rate if it exceeds the stated limit
+    // Note we need to be using volumetric extrusion for this to work as Ennn is in mm³ not mm
+    // We also check we are not exceeding the E max_speed for the current extruder
+    // We ask Extruder to do all the work, but as Extruder won't even see this gcode until after it has been planned
+    // we need to ask it now passing in the relevant data.
+    if(gcode->has_letter('E')) {
+        float data[2];
+        data[0]= gcode->get_value('E'); // E target (maybe absolute or relative)
+        data[1]= isecs; // inverted seconds for the move
+        if(PublicData::set_value(extruder_checksum, target_checksum, data)) {
+            rate_mm_s *= data[1];
+            //THEKERNEL->streams->printf("Extruder has changed the rate by %f to %f\n", data[1], rate_mm_s);
+        }
     }
 
     // Append the block to the planner
@@ -795,12 +803,12 @@ void Robot::append_line(Gcode *gcode, float target[], float rate_mm_s )
                 segment_end[axis] = last_milestone[axis] + segment_delta[axis];
 
             // Append the end of this segment to the queue
-            this->append_milestone(segment_end, rate_mm_s);
+            this->append_milestone(gcode, segment_end, rate_mm_s);
         }
     }
 
     // Append the end of this full move to the queue
-    this->append_milestone(target, rate_mm_s);
+    this->append_milestone(gcode, target, rate_mm_s);
 
     // if adding these blocks didn't start executing, do that now
     THEKERNEL->conveyor->ensure_running();
@@ -908,12 +916,12 @@ void Robot::append_arc(Gcode *gcode, float target[], float offset[], float radiu
         arc_target[this->plane_axis_2] += linear_per_segment;
 
         // Append this segment to the queue
-        this->append_milestone(arc_target, this->feed_rate / seconds_per_minute);
+        this->append_milestone(gcode, arc_target, this->feed_rate / seconds_per_minute);
 
     }
 
     // Ensure last segment arrives at target location.
-    this->append_milestone(target, this->feed_rate / seconds_per_minute);
+    this->append_milestone(gcode, target, this->feed_rate / seconds_per_minute);
 }
 
 // Do the math for an arc and add it to the queue
index 90e1867..d42a298 100644 (file)
@@ -56,7 +56,7 @@ class Robot : public Module {
 
     private:
         void distance_in_gcode_is_known(Gcode* gcode);
-        void append_milestone( float target[], float rate_mm_s);
+        void append_milestone( Gcode *gcode, float target[], float rate_mm_s);
         void append_line( Gcode* gcode, float target[], float rate_mm_s);
         //void append_arc(float theta_start, float angular_travel, float radius, float depth, float rate);
         void append_arc( Gcode* gcode, float target[], float offset[], float radius, bool is_clockwise );
index bb0981d..7cc3501 100644 (file)
@@ -46,7 +46,7 @@ void Drillingcycles::on_module_loaded()
         delete this;
         return;
     }
-    
+
     // Settings
     this->on_config_reload(this);
 
@@ -100,11 +100,11 @@ void Drillingcycles::update_sticky(Gcode *gcode)
     if (gcode->has_letter('F')) this->sticky_f = gcode->get_value('F');
     if (gcode->has_letter('Q')) this->sticky_q = gcode->get_value('Q');
     if (gcode->has_letter('P')) this->sticky_p = gcode->get_int('P');
-    
+
     // set retract plane
-    if (this->retract_type == RETRACT_TO_Z) 
+    if (this->retract_type == RETRACT_TO_Z)
         this->r_plane = this->initial_z;
-    else 
+    else
         this->r_plane = this->sticky_r;
 }
 
@@ -167,14 +167,14 @@ void Drillingcycles::make_hole(Gcode *gcode)
     this->send_gcode("G0%s%s", x, y);
     // rapids to retract position (R)
     this->send_gcode("G0 Z%1.4f", this->sticky_r);
-    
+
     // if peck drilling
-    if (this->sticky_q > 0) 
+    if (this->sticky_q > 0)
         this->peck_hole();
     else
         // feed down to depth at feedrate (F and Z)
         this->send_gcode("G1 F%1.4f Z%1.4f", this->sticky_f, this->sticky_z);
-    
+
     // if dwell, wait for x seconds
     if (this->sticky_p > 0) {
         // dwell exprimed in seconds
@@ -184,7 +184,7 @@ void Drillingcycles::make_hole(Gcode *gcode)
         else
             this->send_gcode("G4 P%u", this->sticky_p);
     }
-    
+
     // rapids retract at R-Plane (Initial-Z or R)
     this->send_gcode("G0 Z%1.4f", this->r_plane);
 }
@@ -195,9 +195,9 @@ void Drillingcycles::on_gcode_received(void* argument)
     Gcode *gcode = static_cast<Gcode *>(argument);
 
     // no "G" in gcode, exit...
-    if (! gcode->has_g) 
+    if (! gcode->has_g)
         return;
-    
+
     // "G" value
     int code = gcode->g;
 
@@ -216,13 +216,12 @@ void Drillingcycles::on_gcode_received(void* argument)
         this->reset_sticky();
         // mark cycle started and gcode taken
         this->cycle_started = true;
-        gcode->mark_as_taken();
     }
     // cycle end
     else if (code == 80) {
         // mark cycle endded and gcode taken
         this->cycle_started = false;
-        gcode->mark_as_taken();
+
         // if retract position is R-Plane
         if (this->retract_type == RETRACT_TO_R) {
             // rapids retract at Initial-Z to avoid futur collisions
@@ -242,7 +241,6 @@ void Drillingcycles::on_gcode_received(void* argument)
         if (code == 81 || code == 82 || code == 83) {
             this->update_sticky(gcode);
             this->make_hole(gcode);
-            gcode->mark_as_taken();
         }
     }
 }
index c8ecd98..2fd1f1c 100644 (file)
@@ -577,7 +577,7 @@ void Endstops::on_gcode_received(void *argument)
     Gcode *gcode = static_cast<Gcode *>(argument);
     if ( gcode->has_g) {
         if ( gcode->g == 28 ) {
-            gcode->mark_as_taken();
+
             // G28 is received, we have homing to do
 
             // First wait for the queue to be empty
@@ -644,7 +644,7 @@ void Endstops::on_gcode_received(void *argument)
                         gcode->stream->printf("%s:%d ", endstop_names[i], this->pins[i].get());
                 }
                 gcode->add_nl= true;
-                gcode->mark_as_taken();
+
             }
             break;
 
@@ -653,7 +653,7 @@ void Endstops::on_gcode_received(void *argument)
                 if (gcode->has_letter('Y')) home_offset[1] = gcode->get_value('Y');
                 if (gcode->has_letter('Z')) home_offset[2] = gcode->get_value('Z');
                 gcode->stream->printf("X %5.3f Y %5.3f Z %5.3f\n", home_offset[0], home_offset[1], home_offset[2]);
-                gcode->mark_as_taken();
+
                 break;
 
             case 306: // Similar to M206 and G92 but sets Homing offsets based on current position, Would be M207 but that is taken
@@ -674,7 +674,7 @@ void Endstops::on_gcode_received(void *argument)
                     }
 
                     gcode->stream->printf("Homing Offset: X %5.3f Y %5.3f Z %5.3f\n", home_offset[0], home_offset[1], home_offset[2]);
-                    gcode->mark_as_taken();
+
                 }
                 break;
 
@@ -685,11 +685,10 @@ void Endstops::on_gcode_received(void *argument)
                     gcode->stream->printf(";Trim (mm):\nM666 X%1.3f Y%1.3f Z%1.3f\n", trim_mm[0], trim_mm[1], trim_mm[2]);
                     gcode->stream->printf(";Max Z\nM665 Z%1.3f\n", this->homing_position[2]);
                 }
-                gcode->mark_as_taken();
                 break;
 
             case 665: { // M665 - set max gamma/z height
-                gcode->mark_as_taken();
+
                 float gamma_max = this->homing_position[2];
                 if (gcode->has_letter('Z')) {
                     this->homing_position[2] = gamma_max = gcode->get_value('Z');
@@ -708,7 +707,7 @@ void Endstops::on_gcode_received(void *argument)
 
                     // print the current trim values in mm
                     gcode->stream->printf("X: %5.3f Y: %5.3f Z: %5.3f\n", trim_mm[0], trim_mm[1], trim_mm[2]);
-                    gcode->mark_as_taken();
+
                 }
             break;
 
@@ -732,7 +731,6 @@ void Endstops::on_gcode_received(void *argument)
                     STEPPER[Z_AXIS]->move(z<0, abs(z), f);
                 }
                 gcode->stream->printf("Moved X %d Y %d Z %d F %d steps\n", x, y, z, f);
-                gcode->mark_as_taken();
                 break;
             }
         }
index ec48573..5bc2739 100644 (file)
@@ -24,6 +24,8 @@
 #include "Gcode.h"
 #include "libs/StreamOutput.h"
 #include "PublicDataRequest.h"
+#include "StreamOutputPool.h"
+#include "ExtruderPublicAccess.h"
 
 #include <mri.h>
 
@@ -39,7 +41,6 @@
 #define extruder_default_feed_rate_checksum  CHECKSUM("extruder_default_feed_rate")
 
 // NEW config names
-#define extruder_checksum                    CHECKSUM("extruder")
 
 #define default_feed_rate_checksum           CHECKSUM("default_feed_rate")
 #define steps_per_mm_checksum                CHECKSUM("steps_per_mm")
@@ -60,9 +61,6 @@
 #define retract_zlift_length_checksum        CHECKSUM("retract_zlift_length")
 #define retract_zlift_feedrate_checksum      CHECKSUM("retract_zlift_feedrate")
 
-#define save_state_checksum                  CHECKSUM("save_state")
-#define restore_state_checksum               CHECKSUM("restore_state")
-
 #define X_AXIS      0
 #define Y_AXIS      1
 #define Z_AXIS      2
@@ -82,6 +80,7 @@
 Extruder::Extruder( uint16_t config_identifier, bool single )
 {
     this->absolute_mode = true;
+    this->milestone_absolute_mode = true;
     this->enabled = false;
     this->paused = false;
     this->single_config = single;
@@ -90,6 +89,8 @@ Extruder::Extruder( uint16_t config_identifier, bool single )
     this->volumetric_multiplier = 1.0F;
     this->extruder_multiplier = 1.0F;
     this->stepper_motor= nullptr;
+    this->milestone_last_position= 0;
+    this->max_volumetric_rate= 0;
 
     memset(this->offset, 0, sizeof(this->offset));
 }
@@ -208,12 +209,75 @@ void Extruder::on_get_public_data(void* argument){
     }
 }
 
+// check against maximum speeds and return the rate modifier
+float Extruder::check_max_speeds(float target, float isecs)
+{
+    float rm= 1.0F; // default no rate modification
+    float delta;
+    // get change in E (may be mm or mm³)
+    if(milestone_absolute_mode) {
+        delta= fabsf(target - milestone_last_position); // delta move
+        milestone_last_position= target;
+
+    }else{
+        delta= target;
+        milestone_last_position += target;
+    }
+
+    if(this->max_volumetric_rate > 0 && this->filament_diameter > 0.01F) {
+        // volumetric enabled and check for volumetric rate
+        float v= delta * isecs; // the flow rate in mm³/sec
+
+        // return the rate change needed to stay within the max rate
+        if(v > max_volumetric_rate) {
+            rm = max_volumetric_rate / v;
+            isecs *= rm; // this slows the rate down for the next test
+        }
+        //THEKERNEL->streams->printf("requested flow rate: %f mm³/sec, corrected flow rate: %f  mm³/sec\n", v, v * rm);
+    }
+
+    // check for max speed as well
+    float max_speed= this->stepper_motor->get_max_rate();
+    if(max_speed > 0) {
+        if(this->filament_diameter > 0.01F) {
+            // volumetric so need to convert delta which is mm³ to mm
+            delta *= volumetric_multiplier;
+        }
+
+        float sm= 1.0F;
+        float v= delta * isecs; // the speed in mm/sec
+        if(v > max_speed) {
+            sm *= (max_speed / v);
+        }
+        //THEKERNEL->streams->printf("requested speed: %f mm/sec, corrected speed: %f  mm/sec\n", v, v * sm);
+        rm *= sm;
+    }
+    return rm;
+}
+
 void Extruder::on_set_public_data(void *argument)
 {
     PublicDataRequest *pdr = static_cast<PublicDataRequest *>(argument);
 
     if(!pdr->starts_with(extruder_checksum)) return;
 
+    // handle extrude rates request from robot
+    // TODO if not in volumetric mode then limit speed based on max_speed
+    if(pdr->second_element_is(target_checksum)) {
+        // disabled extruders do not reply NOTE only one enabled extruder supported
+        if(!this->enabled) return;
+
+        float *d= static_cast<float*>(pdr->get_data_ptr());
+        float target= d[0]; // the E passed in on Gcode is in mm³ (maybe absolute or relative)
+        float isecs= d[1]; // inverted secs
+
+        // check against maximum speeds and return rate modifier
+        d[1]= check_max_speeds(target, isecs);
+
+        pdr->set_taken();
+        return;
+    }
+
     // save or restore state
     if(pdr->second_element_is(save_state_checksum)) {
         this->saved_current_position= this->current_position;
@@ -250,7 +314,6 @@ void Extruder::on_gcode_received(void *argument)
             char buf[16];
             int n = snprintf(buf, sizeof(buf), " E:%1.3f ", this->current_position);
             gcode->txt_after_ok.append(buf, n);
-            gcode->mark_as_taken();
 
         } else if (gcode->m == 92 && ( (this->enabled && !gcode->has_letter('P')) || (gcode->has_letter('P') && gcode->get_value('P') == this->identifier) ) ) {
             float spm = this->steps_per_millimeter;
@@ -261,7 +324,6 @@ void Extruder::on_gcode_received(void *argument)
 
             gcode->stream->printf("E:%g ", spm);
             gcode->add_nl = true;
-            gcode->mark_as_taken();
 
         } else if (gcode->m == 200 && ( (this->enabled && !gcode->has_letter('P')) || (gcode->has_letter('P') && gcode->get_value('P') == this->identifier)) ) {
             if (gcode->has_letter('D')) {
@@ -279,13 +341,26 @@ void Extruder::on_gcode_received(void *argument)
                     gcode->stream->printf("Volumetric extrusion is disabled\n");
                 }
             }
-            gcode->mark_as_taken();
+
+        } else if (gcode->m == 203 && ( (this->enabled && !gcode->has_letter('P')) || (gcode->has_letter('P') && gcode->get_value('P') == this->identifier)) ) {
+            // M203 Exxx Vyyy Set maximum feedrates xxx mm/sec and/or yyy mm³/sec
+            if(gcode->get_num_args() == 0) {
+                gcode->stream->printf("E:%g V:%g", this->stepper_motor->get_max_rate(), this->max_volumetric_rate);
+                gcode->add_nl = true;
+
+            }else{
+                if(gcode->has_letter('E')){
+                    this->stepper_motor->set_max_rate(gcode->get_value('E'));
+                }
+                if(gcode->has_letter('V')){
+                    this->max_volumetric_rate= gcode->get_value('V');
+                }
+            }
 
         } else if (gcode->m == 204 && gcode->has_letter('E') &&
                    ( (this->enabled && !gcode->has_letter('P')) || (gcode->has_letter('P') && gcode->get_value('P') == this->identifier)) ) {
             // extruder acceleration M204 Ennn mm/sec^2 (Pnnn sets the specific extruder for M500)
             this->acceleration= gcode->get_value('E');
-            gcode->mark_as_taken();
 
         } else if (gcode->m == 207 && ( (this->enabled && !gcode->has_letter('P')) || (gcode->has_letter('P') && gcode->get_value('P') == this->identifier)) ) {
             // M207 - set retract length S[positive mm] F[feedrate mm/min] Z[additional zlift/hop] Q[zlift feedrate mm/min]
@@ -293,17 +368,18 @@ void Extruder::on_gcode_received(void *argument)
             if(gcode->has_letter('F')) retract_feedrate = gcode->get_value('F')/60.0F; // specified in mm/min converted to mm/sec
             if(gcode->has_letter('Z')) retract_zlift_length = gcode->get_value('Z');
             if(gcode->has_letter('Q')) retract_zlift_feedrate = gcode->get_value('Q');
-            gcode->mark_as_taken();
 
         } else if (gcode->m == 208 && ( (this->enabled && !gcode->has_letter('P')) || (gcode->has_letter('P') && gcode->get_value('P') == this->identifier)) ) {
             // M208 - set retract recover length S[positive mm surplus to the M207 S*] F[feedrate mm/min]
             if(gcode->has_letter('S')) retract_recover_length = gcode->get_value('S');
             if(gcode->has_letter('F')) retract_recover_feedrate = gcode->get_value('F')/60.0F; // specified in mm/min converted to mm/sec
-            gcode->mark_as_taken();
 
         } else if (gcode->m == 221 && this->enabled) { // M221 S100 change flow rate by percentage
-            if(gcode->has_letter('S')) this->extruder_multiplier= gcode->get_value('S')/100.0F;
-            gcode->mark_as_taken();
+            if(gcode->has_letter('S')) {
+                this->extruder_multiplier= gcode->get_value('S')/100.0F;
+            }else{
+                gcode->stream->printf("Flow rate at %6.2f %%\n", this->extruder_multiplier * 100.0F);
+            }
 
         } else if (gcode->m == 500 || gcode->m == 503) { // M500 saves some volatile settings to config override file, M503 just prints the settings
             if( this->single_config ) {
@@ -312,6 +388,10 @@ void Extruder::on_gcode_received(void *argument)
                 gcode->stream->printf(";E retract length, feedrate, zlift length, feedrate:\nM207 S%1.4f F%1.4f Z%1.4f Q%1.4f\n", this->retract_length, this->retract_feedrate*60.0F, this->retract_zlift_length, this->retract_zlift_feedrate);
                 gcode->stream->printf(";E retract recover length, feedrate:\nM208 S%1.4f F%1.4f\n", this->retract_recover_length, this->retract_recover_feedrate*60.0F);
                 gcode->stream->printf(";E acceleration mm/sec^2:\nM204 E%1.4f\n", this->acceleration);
+                gcode->stream->printf(";E max feed rate mm/sec:\nM203 E%1.4f\n", this->stepper_motor->get_max_rate());
+                if(this->max_volumetric_rate > 0) {
+                    gcode->stream->printf(";E max volumetric rate mm³/sec:\nM203 V%1.4f\n", this->max_volumetric_rate);
+                }
 
             } else {
                 gcode->stream->printf(";E Steps per mm:\nM92 E%1.4f P%d\n", this->steps_per_millimeter, this->identifier);
@@ -319,12 +399,16 @@ void Extruder::on_gcode_received(void *argument)
                 gcode->stream->printf(";E retract length, feedrate:\nM207 S%1.4f F%1.4f Z%1.4f Q%1.4f P%d\n", this->retract_length, this->retract_feedrate*60.0F, this->retract_zlift_length, this->retract_zlift_feedrate, this->identifier);
                 gcode->stream->printf(";E retract recover length, feedrate:\nM208 S%1.4f F%1.4f P%d\n", this->retract_recover_length, this->retract_recover_feedrate*60.0F, this->identifier);
                 gcode->stream->printf(";E acceleration mm/sec^2:\nM204 E%1.4f P%d\n", this->acceleration, this->identifier);
+                gcode->stream->printf(";E max feed rate mm/sec:\nM203 E%1.4f P%d\n", this->stepper_motor->get_max_rate(), this->identifier);
+                if(this->max_volumetric_rate > 0) {
+                    gcode->stream->printf(";E max volumetric rate mm³/sec:\nM203 V%1.4f P%d\n", this->max_volumetric_rate, this->identifier);
+                }
             }
-            gcode->mark_as_taken();
+
         } else if( gcode->m == 17 || gcode->m == 18 || gcode->m == 82 || gcode->m == 83 || gcode->m == 84 ) {
             // Mcodes to pass along to on_gcode_execute
             THEKERNEL->conveyor->append_gcode(gcode);
-            gcode->mark_as_taken();
+
         }
 
     }else if(gcode->has_g) {
@@ -332,16 +416,13 @@ void Extruder::on_gcode_received(void *argument)
         if( (gcode->g == 92 && gcode->has_letter('E')) || (gcode->g == 90 || gcode->g == 91) ) {
             // Gcodes to pass along to on_gcode_execute
             THEKERNEL->conveyor->append_gcode(gcode);
-            gcode->mark_as_taken();
 
         }else if( this->enabled && gcode->g < 4 && gcode->has_letter('E') && !gcode->has_letter('X') && !gcode->has_letter('Y') && !gcode->has_letter('Z') ) {
             // This is a solo move, we add an empty block to the queue to prevent subsequent gcodes being executed at the same time
             THEKERNEL->conveyor->append_gcode(gcode);
             THEKERNEL->conveyor->queue_head_block();
-            gcode->mark_as_taken();
 
         }else if( this->enabled && (gcode->g == 10 || gcode->g == 11) ) { // firmware retract command
-            gcode->mark_as_taken();
             // check we are in the correct state of retract or unretract
             if(gcode->g == 10 && !retracted) {
                 this->retracted= true;
@@ -386,6 +467,25 @@ void Extruder::on_gcode_received(void *argument)
             this->cancel_zlift_restore= true;
         }
     }
+
+    // handle some codes now for the volumetric rate limiting
+    // G90 G91 G92 M82 M83
+    if(gcode->has_m) {
+        switch(gcode->m) {
+            case 82: this->milestone_absolute_mode = true; break;
+            case 83: this->milestone_absolute_mode = false; break;
+        }
+
+    }else if(gcode->has_g) {
+        switch(gcode->g) {
+            case 90: this->milestone_absolute_mode = true; break;
+            case 91: this->milestone_absolute_mode = false; break;
+            case 92:
+                if(gcode->has_letter('E')) { this->milestone_last_position= gcode->get_value('E'); }
+                else if(gcode->get_num_args() == 0) { this->milestone_last_position= 0; }
+                break;
+        }
+    }
 }
 
 // Compute extrusion speed based on parameters and gcode distance of travel
@@ -455,7 +555,7 @@ void Extruder::on_gcode_execute(void *argument)
         } else if (gcode->g == 0 || gcode->g == 1) {
             // Extrusion length from 'G' Gcode
             if( gcode->has_letter('E' )) {
-                // Get relative extrusion distance depending on mode ( in absolute mode we must substract target_position )
+                // Get relative extrusion distance depending on mode ( in absolute mode we must subtract target_position )
                 float extrusion_distance = gcode->get_value('E');
                 float relative_extrusion_distance = extrusion_distance;
                 if (this->absolute_mode) {
@@ -473,7 +573,6 @@ void Extruder::on_gcode_execute(void *argument)
                     // We move proportionally to the robot's movement
                     this->mode = FOLLOW;
                     this->travel_ratio = (relative_extrusion_distance * this->volumetric_multiplier * this->extruder_multiplier) / gcode->millimeters_of_travel; // adjust for volumetric extrusion and extruder multiplier
-                    // TODO: check resulting flowrate, limit robot speed if it exceeds max_speed
                 }
 
                 this->en_pin.set(0);
index 362d8d5..f6a3502 100644 (file)
@@ -40,6 +40,7 @@ class Extruder : public Tool {
         void on_get_public_data(void* argument);
         void on_set_public_data(void* argument);
         uint32_t rate_increase() const;
+        float check_max_speeds(float target, float isecs);
 
         StepperMotor*  stepper_motor;
         Pin            step_pin;                     // Step pin for the stepper driver
@@ -61,7 +62,9 @@ class Extruder : public Tool {
 
         float saved_current_position;
         float volumetric_multiplier;
-        float feed_rate;               // mm/sec for SOLO moves only
+        float feed_rate;                // default rate mm/sec for SOLO moves only
+        float milestone_last_position;  // used for calculating volumemetric rate, last position in mm³
+        float max_volumetric_rate;      // used for calculating volumetric rate in mm³/sec
 
         float travel_ratio;
         float travel_distance;
@@ -81,6 +84,7 @@ class Extruder : public Tool {
             bool single_config:1;
             bool retracted:1;
             bool cancel_zlift_restore:1; // hack to stop a G11 zlift restore from overring an absolute Z setting
+            bool milestone_absolute_mode:1;
         };
 
 
diff --git a/src/modules/tools/extruder/ExtruderPublicAccess.h b/src/modules/tools/extruder/ExtruderPublicAccess.h
new file mode 100644 (file)
index 0000000..d5c16cd
--- /dev/null
@@ -0,0 +1,6 @@
+#pragma once
+
+#define extruder_checksum                    CHECKSUM("extruder")
+#define save_state_checksum                  CHECKSUM("save_state")
+#define restore_state_checksum               CHECKSUM("restore_state")
+#define target_checksum                      CHECKSUM("target")
index 354ddde..d843c64 100644 (file)
@@ -199,10 +199,8 @@ void SCARAcal::on_gcode_received(void *argument)
                                  actuators[0],
                                  actuators[1]);    // display actuator angles Theta and Psi.
                 gcode->txt_after_ok.append(buf, n);
-                gcode->mark_as_taken();
-
             }
-            return;
+            break;
 
             case 360: {
                 float target[2] = {0.0F, 120.0F},
@@ -228,9 +226,9 @@ void SCARAcal::on_gcode_received(void *argument)
                     this->home();                                                   // home
                     SCARA_ang_move(target[0], target[1], 100.0F, slow_rate * 3.0F); // move to target
                 }
-                gcode->mark_as_taken();
             }
-            return;
+            break;
+
             case 361: {
                 float target[2] = {90.0F, 130.0F};
                 if(gcode->has_letter('P')) {
@@ -247,10 +245,11 @@ void SCARAcal::on_gcode_received(void *argument)
                     this->home();                                                   // home - This time leave trims as adjusted.
                     SCARA_ang_move(target[0], target[1], 100.0F, slow_rate * 3.0F); // move to target
                 }
-                gcode->mark_as_taken();
+
             }
-            return;
-              case 364: {
+            break;
+
+            case 364: {
                 float target[2] = {45.0F, 135.0F},
                       S_trim[3];
 
@@ -272,9 +271,8 @@ void SCARAcal::on_gcode_received(void *argument)
                     this->home();                                                                       // home
                     SCARA_ang_move(target[0], target[1], 100.0F, slow_rate * 3.0F);                     // move to target
                 }
-                gcode->mark_as_taken();
             }
-            return;
+            break;
 
             /* TODO case 365: {   // set scara scaling
               std::map<char, float> buf = gcode->get_args();
@@ -289,14 +287,11 @@ void SCARAcal::on_gcode_received(void *argument)
 
               //stream->printf("Set scaling to X:%f Y:%f Z:%f\n", x, y, z);
 
+        */
 
-              gcode->mark_as_taken();*/
-
-            case 366: {                                      // Translate trims to the actual endstop offsets for SCARA
+            case 366:                                       // Translate trims to the actual endstop offsets for SCARA
                 this->translate_trim(gcode->stream);
-
-                gcode->mark_as_taken();
-            }
+                break;
 
         }
     }
index 24c19f9..fcacb9c 100644 (file)
@@ -50,7 +50,7 @@ void Spindle::on_module_loaded()
     current_pwm_value = 0;
     time_since_update = 0;
     spindle_on = true;
-    
+
     if (!THEKERNEL->config->value(spindle_enable_checksum)->by_default(false)->as_bool())
     {
       delete this; // Spindle control module is disabled
@@ -62,14 +62,14 @@ void Spindle::on_module_loaded()
     control_P_term = THEKERNEL->config->value(spindle_control_P_checksum)->by_default(0.0001f)->as_number();
     control_I_term = THEKERNEL->config->value(spindle_control_I_checksum)->by_default(0.0001f)->as_number();
     control_D_term = THEKERNEL->config->value(spindle_control_D_checksum)->by_default(0.0001f)->as_number();
-    
+
     // Smoothing value is low pass filter time constant in seconds.
     float smoothing_time = THEKERNEL->config->value(spindle_control_smoothing_checksum)->by_default(0.1f)->as_number();
     if (smoothing_time * UPDATE_FREQ < 1.0f)
         smoothing_decay = 1.0f;
     else
         smoothing_decay = 1.0f / (UPDATE_FREQ * smoothing_time);
-    
+
     // Get the pin for hardware pwm
     {
         Pin *smoothie_pin = new Pin();
@@ -78,18 +78,18 @@ void Spindle::on_module_loaded()
         output_inverted = smoothie_pin->inverting;
         delete smoothie_pin;
     }
-    
+
     if (spindle_pin == NULL)
     {
         THEKERNEL->streams->printf("Error: Spindle PWM pin must be P2.0-2.5 or other PWM pin\n");
         delete this;
         return;
     }
-    
+
     int period = THEKERNEL->config->value(spindle_pwm_period_checksum)->by_default(1000)->as_int();
     spindle_pin->period_us(period);
     spindle_pin->write(output_inverted ? 1 : 0);
-    
+
     // Get the pin for interrupt
     {
         Pin *smoothie_pin = new Pin();
@@ -110,7 +110,7 @@ void Spindle::on_module_loaded()
         }
         delete smoothie_pin;
     }
-    
+
     THEKERNEL->slow_ticker->attach(UPDATE_FREQ, this, &Spindle::on_update_speed);
     register_for_event(ON_GCODE_RECEIVED);
     register_for_event(ON_GCODE_EXECUTE);
@@ -133,10 +133,10 @@ uint32_t Spindle::on_update_speed(uint32_t dummy)
     else
         time_since_update++;
     last_irq = new_irq;
-    
+
     if (time_since_update > UPDATE_FREQ)
         last_time = 0;
-    
+
     // Calculate current RPM
     uint32_t t = last_time;
     if (t == 0)
@@ -148,21 +148,21 @@ uint32_t Spindle::on_update_speed(uint32_t dummy)
         float new_rpm = 1000000 * 60.0f / (t * pulses_per_rev);
         current_rpm = smoothing_decay * new_rpm + (1.0f - smoothing_decay) * current_rpm;
     }
-    
+
     if (spindle_on)
     {
         float error = target_rpm - current_rpm;
-        
+
         current_I_value += control_I_term * error * 1.0f / UPDATE_FREQ;
         current_I_value = confine(current_I_value, -1.0f, 1.0f);
-        
+
         float new_pwm = 0.5f;
         new_pwm += control_P_term * error;
         new_pwm += current_I_value;
         new_pwm += control_D_term * UPDATE_FREQ * (error - prev_error);
         new_pwm = confine(new_pwm, 0.0f, 1.0f);
         prev_error = error;
-        
+
         current_pwm_value = new_pwm;
     }
     else
@@ -170,12 +170,12 @@ uint32_t Spindle::on_update_speed(uint32_t dummy)
         current_I_value = 0;
         current_pwm_value = 0;
     }
-    
+
     if (output_inverted)
         spindle_pin->write(1.0f - current_pwm_value);
     else
         spindle_pin->write(current_pwm_value);
-    
+
     return 0;
 }
 
@@ -183,7 +183,7 @@ uint32_t Spindle::on_update_speed(uint32_t dummy)
 void Spindle::on_gcode_received(void* argument)
 {
     Gcode *gcode = static_cast<Gcode *>(argument);
-    
+
     if (gcode->has_m)
     {
         if (gcode->m == 957)
@@ -191,7 +191,6 @@ void Spindle::on_gcode_received(void* argument)
             // M957: report spindle speed
             THEKERNEL->streams->printf("Current RPM: %5.0f  Target RPM: %5.0f  PWM value: %5.3f\n",
                                        current_rpm, target_rpm, current_pwm_value);
-            gcode->mark_as_taken();
         }
         else if (gcode->m == 958)
         {
@@ -209,7 +208,6 @@ void Spindle::on_gcode_received(void* argument)
         {
             // M3: Spindle on, M5: Spindle off
             THEKERNEL->conveyor->append_gcode(gcode);
-            gcode->mark_as_taken();
         }
     }
 }
@@ -217,14 +215,14 @@ void Spindle::on_gcode_received(void* argument)
 void Spindle::on_gcode_execute(void* argument)
 {
     Gcode *gcode = static_cast<Gcode *>(argument);
-    
+
     if (gcode->has_m)
     {
         if (gcode->m == 3)
         {
             // M3: Spindle on
             spindle_on = true;
-            
+
             if (gcode->has_letter('S'))
             {
                 target_rpm = gcode->get_value('S');
index e9852eb..1aa2e64 100644 (file)
@@ -73,7 +73,7 @@ void Switch::on_config_reload(void *argument)
     this->output_on_command =    THEKERNEL->config->value(switch_checksum, this->name_checksum, output_on_command_checksum )->by_default("")->as_string();
     this->output_off_command =   THEKERNEL->config->value(switch_checksum, this->name_checksum, output_off_command_checksum )->by_default("")->as_string();
     this->switch_state =         THEKERNEL->config->value(switch_checksum, this->name_checksum, startup_state_checksum )->by_default(false)->as_bool();
-    string type =                THEKERNEL->config->value(switch_checksum, this->name_checksum, output_type_checksum )->by_default("")->as_string();
+    string type =                THEKERNEL->config->value(switch_checksum, this->name_checksum, output_type_checksum )->by_default("pwm")->as_string();
 
     if(type == "pwm"){
         this->output_type= SIGMADELTA;
@@ -197,22 +197,30 @@ void Switch::on_gcode_received(void *argument)
         return;
     }
 
-    // drain queue
-    THEKERNEL->conveyor->wait_for_empty_queue();
-
+    // we need to sync this with the queue, so we need to wait for queue to empty, however due to certain slicers
+    // issuing redundant swicth on calls regularly we need to optimize by making sure the value is actually changing
+    // hence we need to do the wait for queue in each case rather than just once at the start
     if(match_input_on_gcode(gcode)) {
         if (this->output_type == SIGMADELTA) {
             // SIGMADELTA output pin turn on (or off if S0)
             if(gcode->has_letter('S')) {
                 int v = round(gcode->get_value('S') * sigmadelta_pin->max_pwm() / 255.0); // scale by max_pwm so input of 255 and max_pwm of 128 would set value to 128
-                this->sigmadelta_pin->pwm(v);
-                this->switch_state= (v > 0);
+                if(v != this->sigmadelta_pin->get_pwm()){ // optimize... ignore if already set to the same pwm
+                    // drain queue
+                    THEKERNEL->conveyor->wait_for_empty_queue();
+                    this->sigmadelta_pin->pwm(v);
+                    this->switch_state= (v > 0);
+                }
             } else {
+                // drain queue
+                THEKERNEL->conveyor->wait_for_empty_queue();
                 this->sigmadelta_pin->pwm(this->switch_value);
                 this->switch_state= (this->switch_value > 0);
             }
 
         } else if (this->output_type == HWPWM) {
+            // drain queue
+            THEKERNEL->conveyor->wait_for_empty_queue();
             // PWM output pin set duty cycle 0 - 100
             if(gcode->has_letter('S')) {
                 float v = gcode->get_value('S');
@@ -226,12 +234,16 @@ void Switch::on_gcode_received(void *argument)
             }
 
         } else if (this->output_type == DIGITAL) {
+            // drain queue
+            THEKERNEL->conveyor->wait_for_empty_queue();
             // logic pin turn on
             this->digital_pin->set(true);
             this->switch_state = true;
         }
 
     } else if(match_input_off_gcode(gcode)) {
+        // drain queue
+        THEKERNEL->conveyor->wait_for_empty_queue();
         this->switch_state = false;
         if (this->output_type == SIGMADELTA) {
             // SIGMADELTA output pin
index 74df090..3151bde 100644 (file)
@@ -21,6 +21,7 @@ PID_Autotuner::PID_Autotuner()
     peaks = NULL;
     tick = false;
     tickCnt = 0;
+    nLookBack = 10 * 20; // 10 seconds of lookback (fixed 20ms tick period)
 }
 
 void PID_Autotuner::on_module_loaded()
@@ -35,7 +36,6 @@ void PID_Autotuner::begin(float target, StreamOutput *stream, int ncycles)
 {
     noiseBand = 0.5;
     oStep = temp_control->heater_pin.max_pwm(); // use max pwm to cycle temp
-    nLookBack = 5 * 20; // 5 seconds of lookback
     lookBackCnt = 0;
     tickCnt = 0;
 
@@ -60,12 +60,8 @@ void PID_Autotuner::begin(float target, StreamOutput *stream, int ncycles)
     peakType = 0;
     peakCount = 0;
     justchanged = false;
-
-    float refVal = temp_control->get_temperature();
-    absMax = refVal;
-    absMin = refVal;
-    output = oStep;
-    temp_control->heater_pin.pwm(oStep); // turn on to start heating
+    firstPeak= false;
+    output= 0;
 
     s->printf("%s: Starting PID Autotune, %d max cycles, M304 aborts\n", temp_control->designator.c_str(), ncycles);
 }
@@ -97,11 +93,9 @@ void PID_Autotuner::on_gcode_received(void *argument)
 
     if(gcode->has_m) {
         if(gcode->m == 304) {
-            gcode->mark_as_taken();
             abort();
 
         } else if (gcode->m == 303 && gcode->has_letter('E')) {
-            gcode->mark_as_taken();
             int pool_index = gcode->get_value('E');
 
             // get the temperature control instance with this pool index
@@ -116,15 +110,30 @@ void PID_Autotuner::on_gcode_received(void *argument)
                 return;
             }
 
+            // set target
             float target = 150.0;
             if (gcode->has_letter('S')) {
                 target = gcode->get_value('S');
                 gcode->stream->printf("Target: %5.1f\n", target);
             }
+
+            // set the cycles, really not needed for this new version
             int ncycles = 8;
             if (gcode->has_letter('C')) {
                 ncycles = gcode->get_value('C');
+                if(ncycles < 8) ncycles= 8;
+            }
+
+            // optionally set the noise band, default is 0.5
+            if (gcode->has_letter('B')) {
+                noiseBand = gcode->get_value('B');
+            }
+
+            // optionally set the look back in seconds default is 10 seconds
+            if (gcode->has_letter('L')) {
+                nLookBack = gcode->get_value('L');
             }
+
             gcode->stream->printf("Start PID tune for index E%d, designator: %s\n", pool_index, this->temp_control->designator.c_str());
             this->begin(target, gcode->stream, ncycles);
         }
@@ -136,7 +145,7 @@ uint32_t PID_Autotuner::on_tick(uint32_t dummy)
     if (temp_control != NULL)
         tick = true;
 
-    tickCnt += 1000 / 20; // millisecond tick count
+    tickCnt += (1000 / 20); // millisecond tick count
     return 0;
 }
 
@@ -154,28 +163,40 @@ void PID_Autotuner::on_idle(void *)
         return;
 
     if(peakCount >= requested_cycles) {
+        s->printf("// WARNING: Autopid did not resolve within %d cycles, these results are probably innacurate\n", requested_cycles);
         finishUp();
         return;
     }
 
     float refVal = temp_control->get_temperature();
 
-    if (refVal > absMax) absMax = refVal;
-    if (refVal < absMin) absMin = refVal;
-
     // oscillate the output base on the input's relation to the setpoint
     if (refVal > target_temperature + noiseBand) {
         output = 0;
         //temp_control->heater_pin.pwm(output);
         temp_control->heater_pin.set(0);
+        if(!firstPeak) {
+            firstPeak= true;
+            absMax= refVal;
+            absMin= refVal;
+        }
+
     } else if (refVal < target_temperature - noiseBand) {
         output = oStep;
         temp_control->heater_pin.pwm(output);
     }
 
-    bool isMax = true, isMin = true;
+    if ((tickCnt % 1000) == 0) {
+        s->printf("// Autopid Status - %5.1f/%5.1f @%d %d/%d\n",  refVal, target_temperature, output, peakCount, requested_cycles);
+    }
+
+    if(!firstPeak){
+        // we wait until we hit the first peak befire we do anything else,we need to ignore the itial warmup temperatures
+        return;
+    }
 
-    // id peaks
+    // find the peaks high and low
+    bool isMax = true, isMin = true;
     for (int i = nLookBack - 1; i >= 0; i--) {
         float val = lastInputs[i];
         if (isMax) isMax = refVal > val;
@@ -185,13 +206,15 @@ void PID_Autotuner::on_idle(void *)
 
     lastInputs[0] = refVal;
 
+    //we don't want to trust the maxes or mins until the inputs array has been filled
     if (lookBackCnt < nLookBack) {
         lookBackCnt++; // count number of times we have filled lastInputs
-        //we don't want to trust the maxes or mins until the inputs array has been filled
         return;
     }
 
     if (isMax) {
+        if(refVal > absMax) absMax= refVal;
+
         if (peakType == 0) peakType = 1;
         if (peakType == -1) {
             peakType = 1;
@@ -202,6 +225,7 @@ void PID_Autotuner::on_idle(void *)
         peaks[peakCount] = refVal;
 
     } else if (isMin) {
+        if(refVal < absMin) absMin= refVal;
         if (peakType == 0) peakType = -1;
         if (peakType == 1) {
             peakType = -1;
@@ -212,28 +236,22 @@ void PID_Autotuner::on_idle(void *)
         if (peakCount < requested_cycles) peaks[peakCount] = refVal;
     }
 
-    // we need to ignore the first cycle warming up from room temp
-
-    if (justchanged && peakCount > 2) {
-        if(peakCount == 3) { // reset min to new min
-            absMin = refVal;
-        }
-        //we've transitioned. check if we can autotune based on the last peaks
+    if (justchanged && peakCount >= 4) {
+        // we've transitioned. check if we can autotune based on the last peaks
         float avgSeparation = (std::abs(peaks[peakCount - 1] - peaks[peakCount - 2]) + std::abs(peaks[peakCount - 2] - peaks[peakCount - 3])) / 2;
-        s->printf("Cycle %d: max: %g, min: %g, avg separation: %g\n", peakCount, absMax, absMin, avgSeparation);
-        if (peakCount > 3 && avgSeparation < 0.05 * (absMax - absMin)) {
+        s->printf("// Cycle %d: max: %g, min: %g, avg separation: %g\n", peakCount, absMax, absMin, avgSeparation);
+        if (peakCount > 3 && avgSeparation < (0.05 * (absMax - absMin))) {
             DEBUG_PRINTF("Stabilized\n");
             finishUp();
             return;
         }
     }
 
-    justchanged = false;
-
     if ((tickCnt % 1000) == 0) {
-        s->printf("%s: %5.1f/%5.1f @%d %d/%d\n", temp_control->designator.c_str(), refVal, target_temperature, output, peakCount, requested_cycles);
         DEBUG_PRINTF("lookBackCnt= %d, peakCount= %d, absmax= %g, absmin= %g, peak1= %lu, peak2= %lu\n", lookBackCnt, peakCount, absMax, absMin, peak1, peak2);
     }
+
+    justchanged = false;
 }
 
 
index 2cfb38e..dbf9214 100644 (file)
@@ -31,8 +31,6 @@ private:
     float target_temperature;
     StreamOutput *s;
 
-    volatile bool tick;
-
     float *peaks;
     int requested_cycles;
     float noiseBand;
@@ -43,11 +41,15 @@ private:
     int peakType;
     float *lastInputs;
     int peakCount;
-    bool justchanged;
     float absMax, absMin;
     float oStep;
     int output;
     volatile unsigned long tickCnt;
+    struct {
+        bool justchanged:1;
+        volatile bool tick:1;
+        bool firstPeak:1;
+    };
 };
 
 #endif /* _PID_AUTOTUNE_H */
index 36c1fda..0d493ab 100644 (file)
@@ -206,14 +206,12 @@ void TemperatureControl::on_gcode_received(void *argument)
 
         if( gcode->m == this->get_m_code ) {
             char buf[32]; // should be big enough for any status
-            int n = snprintf(buf, sizeof(buf), "%s:%3.1f /%3.1f @%d ", this->designator.c_str(), this->get_temperature(), ((target_temperature == UNDEFINED) ? 0.0 : target_temperature), this->o);
+            int n = snprintf(buf, sizeof(buf), "%s:%3.1f /%3.1f @%d ", this->designator.c_str(), this->get_temperature(), ((target_temperature <= 0) ? 0.0 : target_temperature), this->o);
             gcode->txt_after_ok.append(buf, n);
-            gcode->mark_as_taken();
             return;
         }
 
         if (gcode->m == 305) { // set or get sensor settings
-            gcode->mark_as_taken();
             if (gcode->has_letter('S') && (gcode->get_value('S') == this->pool_index)) {
                 TempSensor::sensor_options_t args= gcode->get_args();
                 args.erase('S'); // don't include the S
@@ -236,7 +234,7 @@ void TemperatureControl::on_gcode_received(void *argument)
                 if(sensor->get_optional(options)) {
                     for(auto &i : options) {
                         // foreach optional value
-                        gcode->stream->printf("%s(S%d): %c%1.18f\n", this->designator.c_str(), this->pool_index, i.first, i.second);
+                        gcode->stream->printf("%s(S%d): %c %1.18f\n", this->designator.c_str(), this->pool_index, i.first, i.second);
                     }
                 }
             }
@@ -248,7 +246,6 @@ void TemperatureControl::on_gcode_received(void *argument)
         if(this->readonly) return;
 
         if (gcode->m == 301) {
-            gcode->mark_as_taken();
             if (gcode->has_letter('S') && (gcode->get_value('S') == this->pool_index)) {
                 if (gcode->has_letter('P'))
                     setPIDp( gcode->get_value('P') );
@@ -279,10 +276,8 @@ void TemperatureControl::on_gcode_received(void *argument)
                     gcode->stream->printf("\n");
                 }
             }
-            gcode->mark_as_taken();
 
         } else if( ( gcode->m == this->set_m_code || gcode->m == this->set_and_wait_m_code ) && gcode->has_letter('S')) {
-            gcode->mark_as_taken();
             // this only gets handled if it is not controlled by the tool manager or is active in the toolmanager
             this->active = true;
 
@@ -347,7 +342,7 @@ void TemperatureControl::on_get_public_data(void *argument)
     // ok this is targeted at us, so send back the requested data
     if(pdr->third_element_is(current_temperature_checksum)) {
         this->public_data_return.current_temperature = this->get_temperature();
-        this->public_data_return.target_temperature = (target_temperature == UNDEFINED) ? 0 : this->target_temperature;
+        this->public_data_return.target_temperature = (target_temperature <= 0) ? 0 : this->target_temperature;
         this->public_data_return.pwm = this->o;
         this->public_data_return.designator= this->designator;
         pdr->set_data_ptr(&this->public_data_return);
@@ -385,11 +380,11 @@ void TemperatureControl::set_desired_temperature(float desired_temperature)
 
     float last_target_temperature= target_temperature;
     target_temperature = desired_temperature;
-    if (desired_temperature == 0.0F){
+    if (desired_temperature <= 0.0F){
         // turning it off
         heater_pin.set((this->o = 0));
 
-    }else if(last_target_temperature == 0.0F) {
+    }else if(last_target_temperature <= 0.0F) {
         // if it was off and we are now turning it on we need to initialize
         this->lastInput= last_reading;
         // set to whatever the output currently is See http://brettbeauregard.com/blog/2011/04/improving-the-beginner%E2%80%99s-pid-initialization/
@@ -407,12 +402,7 @@ float TemperatureControl::get_temperature()
 uint32_t TemperatureControl::thermistor_read_tick(uint32_t dummy)
 {
     float temperature = sensor->get_temperature();
-    if(this->readonly) {
-        last_reading = temperature;
-        return 0;
-    }
-
-    if (target_temperature > 0) {
+    if(!this->readonly && target_temperature > 2) {
         if (isinf(temperature) || temperature < min_temp) {
             this->min_temp_violated = true;
             target_temperature = UNDEFINED;
@@ -420,9 +410,8 @@ uint32_t TemperatureControl::thermistor_read_tick(uint32_t dummy)
         } else {
             pid_process(temperature);
         }
-    } else {
-        heater_pin.set((this->o = 0));
     }
+
     last_reading = temperature;
     return 0;
 }
@@ -481,7 +470,7 @@ void TemperatureControl::pid_process(float temperature)
 void TemperatureControl::on_second_tick(void *argument)
 {
     if (waiting)
-        THEKERNEL->streams->printf("%s:%3.1f /%3.1f @%d\n", designator.c_str(), get_temperature(), ((target_temperature == UNDEFINED) ? 0.0 : target_temperature), o);
+        THEKERNEL->streams->printf("%s:%3.1f /%3.1f @%d\n", designator.c_str(), get_temperature(), ((target_temperature <= 0) ? 0.0 : target_temperature), o);
 }
 
 void TemperatureControl::setPIDp(float p)
index cf1814e..a391c40 100644 (file)
@@ -44,6 +44,9 @@ Thermistor::Thermistor()
     this->bad_config = false;
     this->use_steinhart_hart= false;
     this->beta= 0.0F; // not used by default
+    min_temp= 999;
+    max_temp= 0;
+    this->thermistor_number= 0; // not a predefined thermistor
 }
 
 Thermistor::~Thermistor()
@@ -64,11 +67,13 @@ void Thermistor::UpdateConfig(uint16_t module_checksum, uint16_t name_checksum)
     bool use_beta_table= THEKERNEL->config->value(module_checksum, name_checksum, use_beta_table_checksum)->by_default(false)->as_bool();
 
     bool found= false;
+    int cnt= 0;
     // load a predefined thermistor name if found
     string thermistor = THEKERNEL->config->value(module_checksum, name_checksum, thermistor_checksum)->by_default("")->as_string();
     if(!thermistor.empty()) {
         if(!use_beta_table) {
             for (auto& i : predefined_thermistors) {
+                cnt++;
                 if(thermistor.compare(i.name) == 0) {
                     this->c1 = i.c1;
                     this->c2 = i.c2;
@@ -84,7 +89,9 @@ void Thermistor::UpdateConfig(uint16_t module_checksum, uint16_t name_checksum)
 
         // fall back to the old beta pre-defined table if not found above
         if(!found) {
+            cnt= 0;
             for (auto& i : predefined_thermistors_beta) {
+                cnt++;
                 if(thermistor.compare(i.name) == 0) {
                     this->beta = i.beta;
                     this->r0 = i.r0;
@@ -92,11 +99,18 @@ void Thermistor::UpdateConfig(uint16_t module_checksum, uint16_t name_checksum)
                     this->r1 = i.r1;
                     this->r2 = i.r2;
                     use_steinhart_hart= false;
+                    cnt |= 0x80; // set MSB to indicate beta table
                     found= true;
                     break;
                 }
             }
         }
+
+        if(!found) {
+            thermistor_number= 0;
+        }else{
+            thermistor_number= cnt;
+        }
     }
 
     // Preset values are overriden by specified values
@@ -207,7 +221,11 @@ void Thermistor::calc_jk()
 float Thermistor::get_temperature()
 {
     if(bad_config) return infinityf();
-    return adc_value_to_temperature(new_thermistor_reading());
+    float t= adc_value_to_temperature(new_thermistor_reading());
+    // keep track of min/max for M305
+    if(t > max_temp) max_temp= t;
+    if(t < min_temp) min_temp= t;
+    return t;
 }
 
 void Thermistor::get_raw()
@@ -217,32 +235,60 @@ void Thermistor::get_raw()
     }
 
     int adc_value= new_thermistor_reading();
+    const uint32_t max_adc_value= THEKERNEL->adc->get_max_value();
+
      // resistance of the thermistor in ohms
-    float r = r2 / ((4095.0F / adc_value) - 1.0F);
+    float r = r2 / (((float)max_adc_value / adc_value) - 1.0F);
     if (r1 > 0.0F) r = (r1 * r) / (r1 - r);
 
     THEKERNEL->streams->printf("adc= %d, resistance= %f\n", adc_value, r);
 
+    float t;
     if(this->use_steinhart_hart) {
         THEKERNEL->streams->printf("S/H c1= %1.18f, c2= %1.18f, c3= %1.18f\n", c1, c2, c3);
         float l = logf(r);
-        float t= (1.0F / (this->c1 + this->c2 * l + this->c3 * powf(l,3))) - 273.15F;
-        THEKERNEL->streams->printf("S/H temp= %f\n", t);
+        t= (1.0F / (this->c1 + this->c2 * l + this->c3 * powf(l,3))) - 273.15F;
+        THEKERNEL->streams->printf("S/H temp= %f, min= %f, max= %f, delta= %f\n", t, min_temp, max_temp, max_temp-min_temp);
     }else{
-        float t= (1.0F / (k + (j * logf(r / r0)))) - 273.15F;
-        THEKERNEL->streams->printf("beta temp= %f\n", t);
+        t= (1.0F / (k + (j * logf(r / r0)))) - 273.15F;
+        THEKERNEL->streams->printf("beta temp= %f, min= %f, max= %f, delta= %f\n", t, min_temp, max_temp, max_temp-min_temp);
+    }
+
+    // print out predefined thermistors
+    int cnt= 1;
+    THEKERNEL->streams->printf("S/H table\n");
+    for (auto& i : predefined_thermistors) {
+        THEKERNEL->streams->printf("%d - %s\n", cnt++, i.name);
+    }
+
+    cnt= 129;
+    THEKERNEL->streams->printf("Beta table\n");
+    for (auto& i : predefined_thermistors_beta) {
+        THEKERNEL->streams->printf("%d - %s\n", cnt++, i.name);
+    }
+
+    // if using a predefined thermistor show its name and which table it is from
+    if(thermistor_number != 0) {
+        string name= (thermistor_number&0x80) ? predefined_thermistors_beta[(thermistor_number&0x7F)-1].name :  predefined_thermistors[thermistor_number-1].name;
+        THEKERNEL->streams->printf("Using predefined thermistor %d in %s table: %s\n", thermistor_number&0x7F, (thermistor_number&0x80)?"Beta":"S/H", name.c_str());
     }
+
+    // reset the min/max
+    min_temp= max_temp= t;
 }
 
-float Thermistor::adc_value_to_temperature(int adc_value)
+float Thermistor::adc_value_to_temperature(uint32_t adc_value)
 {
-    if ((adc_value == 4095) || (adc_value == 0))
+    const uint32_t max_adc_value= THEKERNEL->adc->get_max_value();
+    if ((adc_value >= max_adc_value) || (adc_value == 0))
         return infinityf();
 
     // resistance of the thermistor in ohms
-    float r = r2 / ((4095.0F / adc_value) - 1.0F);
+    float r = r2 / (((float)max_adc_value / adc_value) - 1.0F);
     if (r1 > 0.0F) r = (r1 * r) / (r1 - r);
 
+    if(r > this->r0 * 8) return infinityf(); // 800k is probably open circuit
+
     float t;
     if(this->use_steinhart_hart) {
         float l = logf(r);
@@ -257,24 +303,15 @@ float Thermistor::adc_value_to_temperature(int adc_value)
 
 int Thermistor::new_thermistor_reading()
 {
-    int last_raw = THEKERNEL->adc->read(&thermistor_pin);
-    if (queue.size() >= queue.capacity()) {
-        uint16_t l;
-        queue.pop_front(l);
-    }
-    uint16_t r = last_raw;
-    queue.push_back(r);
-    uint16_t median_buffer[queue.size()];
-    for (int i=0; i<queue.size(); i++)
-      median_buffer[i] = *queue.get_ref(i);
-    uint16_t m = median_buffer[quick_median(median_buffer, queue.size())];
-    return m;
+    // filtering now done in ADC
+    return THEKERNEL->adc->read(&thermistor_pin);
 }
 
 bool Thermistor::set_optional(const sensor_options_t& options) {
     bool define_beta= false;
     bool change_beta= false;
     uint8_t define_shh= 0;
+    uint8_t predefined= 0;
 
     for(auto &i : options) {
         switch(i.first) {
@@ -284,6 +321,53 @@ bool Thermistor::set_optional(const sensor_options_t& options) {
             case 'I': this->c1= i.second; define_shh++; break;
             case 'J': this->c2= i.second; define_shh++; break;
             case 'K': this->c3= i.second; define_shh++; break;
+            case 'P': predefined= roundf(i.second); break;
+        }
+    }
+
+    if(predefined != 0) {
+        if(define_beta || change_beta || define_shh != 0) {
+            // cannot use a predefined with any other option
+            this->bad_config= true;
+            return false;
+        }
+
+        if(predefined & 0x80) {
+            // use the predefined beta table
+            uint8_t n= (predefined&0x7F)-1;
+            if(n >= sizeof(predefined_thermistors_beta) / sizeof(thermistor_beta_table_t)) {
+                // not a valid index
+                return false;
+            }
+            auto &i= predefined_thermistors_beta[n];
+            this->beta = i.beta;
+            this->r0 = i.r0;
+            this->t0 = i.t0;
+            this->r1 = i.r1;
+            this->r2 = i.r2;
+            use_steinhart_hart= false;
+            calc_jk();
+            thermistor_number= predefined;
+            this->bad_config= false;
+            return true;
+
+        }else {
+            // use the predefined S/H table
+            uint8_t n= predefined-1;
+            if(n >= sizeof(predefined_thermistors) / sizeof(thermistor_table_t)) {
+                // not a valid index
+                return false;
+            }
+            auto &i= predefined_thermistors[n];
+            this->c1 = i.c1;
+            this->c2 = i.c2;
+            this->c3 = i.c3;
+            this->r1 = i.r1;
+            this->r2 = i.r2;
+            use_steinhart_hart= true;
+            thermistor_number= predefined;
+            this->bad_config= false;
+            return true;
         }
     }
 
@@ -314,6 +398,11 @@ bool Thermistor::set_optional(const sensor_options_t& options) {
 }
 
 bool Thermistor::get_optional(sensor_options_t& options) {
+    if(thermistor_number != 0) {
+        options['P']= thermistor_number;
+        return true;
+    }
+
     if(use_steinhart_hart) {
         options['I']= this->c1;
         options['J']= this->c2;
index 4ceddb6..9b432fd 100644 (file)
@@ -33,7 +33,7 @@ class Thermistor : public TempSensor
 
     private:
         int new_thermistor_reading();
-        float adc_value_to_temperature(int adc_value);
+        float adc_value_to_temperature(uint32_t adc_value);
         void calc_jk();
 
         // Thermistor computation settings using beta, not used if using Steinhart-Hart
@@ -60,12 +60,12 @@ class Thermistor : public TempSensor
 
         Pin  thermistor_pin;
 
-        RingBuffer<uint16_t,QUEUE_LEN> queue;  // Queue of readings
-
+        float min_temp, max_temp;
         struct {
             bool bad_config:1;
             bool use_steinhart_hart:1;
         };
+        uint8_t thermistor_number;
 };
 
 #endif
index c8fc71c..f2400d9 100644 (file)
@@ -5,6 +5,8 @@ typedef struct {
         float beta, r0, t0;
 } const thermistor_beta_table_t;
 
+// NOTE the order of these tables must NOT be changed as the index can be used in M305 to set the prefined thermistor to use
+
 static const thermistor_beta_table_t predefined_thermistors_beta[] {
     // name,            r1,  r2,   beta,    r0,        t0
     {"EPCOS100K",       0,   4700, 4066.0F, 100000.0F, 25.0F}, // B57540G0104F000
index bc5a022..2dd5d65 100644 (file)
@@ -52,7 +52,6 @@ void ToolManager::on_gcode_received(void *argument){
 
     if( gcode->has_letter('T') ){
         int new_tool = gcode->get_value('T');
-        gcode->mark_as_taken();
         if(new_tool >= (int)this->tools.size() || new_tool < 0){
             // invalid tool
             if( return_error_on_unhandled_gcode ) {
index 49e2b87..89c7c35 100644 (file)
 
     Usage
     -----
-    G32 probes the probe points and defines the bed ZGrid, this will remain in effect until reset or M370
-    G31 reports the status
+    G32                  : probes the probe points and defines the bed ZGrid, this will remain in effect until reset or M370
+    G31                  : reports the status - Display probe data points
 
-    M370 clears the ZGrid and the bed leveling is disabled until G32 is run again
-    M370 X7 Y9 allocates a new grid size of 7x9 and clears as above
+    M370                 : clears the ZGrid and the bed levelling is disabled until G32 is run again
+    M370 X7 Y9           : allocates a new grid size of 7x9 and clears as above
 
-    M371 moves the head to the next calibration postion without saving for manual calibration
-    M372 move the head to the next calibration postion after saving the current probe point to memory - manual calbration
+    M371                 : moves the head to the next calibration position without saving for manual calibration
+    M372                 : move the head to the next calibration position after saving the current probe point to memory - manual calbration
+    M373                 : completes calibration and enables the Z compensation grid
 
-    M373 completes calibration and enables the Z compensation grid
+    M374                 : Save the grid to "Zgrid" on SD card
+    M374 S###            : Save custom grid to "Zgrid.###" on SD card
 
-    M
+    M375                 : Loads grid file "Zgrid" from SD
+    M375 S###            : Load custom grid file "Zgrid.###"
 
-    M500 saves the probe points and the probe offsets
-    M503 displays the current settings
+    M565 X### Y### Z###  : Set new probe offsets
+
+    M500                 : saves the probe offsets
+    M503                 : displays the current settings
 */
 
 #include "ZGridStrategy.h"
@@ -240,6 +245,8 @@ bool ZGridStrategy::handleGcode(Gcode *gcode)
             // M370: Clear current ZGrid for calibration, and move to first position
             case 370: {
                 this->setAdjustFunction(false); // Disable leveling code
+                this->cal[Z_AXIS] = std::get<Z_AXIS>(this->probe_offsets) + zprobe->getProbeHeight();
+
 
                 if(gcode->has_letter('X'))  // Rows (X)
                     this->numRows = gcode->get_value('X');
@@ -365,8 +372,6 @@ bool ZGridStrategy::handleGcode(Gcode *gcode)
                 gcode->stream->printf(";Probe offsets:\n");
                 std::tie(x, y, z) = probe_offsets;
                 gcode->stream->printf("M565 X%1.5f Y%1.5f Z%1.5f\n", x, y, z);
-
-                gcode->mark_as_taken();
                 break;
             }
 
@@ -504,7 +509,8 @@ bool ZGridStrategy::doProbing(StreamOutput *stream)  // probed calibration
     for (int probes = 0; probes < probe_points; probes++){
         int pindex = 0;
 
-        float z = 5.0f - zprobe->probeDistance((this->cal[X_AXIS] + this->cal_offset_x)-std::get<X_AXIS>(this->probe_offsets),
+        // z = z home offset - probed distance
+        float z = getZhomeoffset() -zprobe->probeDistance((this->cal[X_AXIS] + this->cal_offset_x)-std::get<X_AXIS>(this->probe_offsets),
                                                (this->cal[Y_AXIS] + this->cal_offset_y)-std::get<Y_AXIS>(this->probe_offsets));
 
         pindex = int(this->cal[X_AXIS]/this->bed_div_x + 0.25)*this->numCols + int(this->cal[Y_AXIS]/this->bed_div_y + 0.25);
@@ -581,7 +587,7 @@ void ZGridStrategy::move(float *position, float feed)
     // Assemble Gcode to add onto the queue.  Also translate the position for non standard cartesian spaces (cal_offset)
     snprintf(cmd, sizeof(cmd), "G0 X%1.3f Y%1.3f Z%1.3f F%1.1f", position[0] + this->cal_offset_x, position[1] + this->cal_offset_y, position[2], feed * 60); // use specified feedrate (mm/sec)
 
-    THEKERNEL->streams->printf("DEBUG: move: %s cent: %i\n", cmd, this->center_zero);
+    //THEKERNEL->streams->printf("DEBUG: move: %s cent: %i\n", cmd, this->center_zero);
 
     Gcode gc(cmd, &(StreamOutput::NullStream));
     THEKERNEL->robot->on_gcode_received(&gc); // send to robot directly
@@ -589,14 +595,14 @@ void ZGridStrategy::move(float *position, float feed)
 
 
 void ZGridStrategy::next_cal(void){
-    if (int(this->cal[X_AXIS] / this->bed_div_x) % 2 != 0){  // Odd row
+    if ((((int) roundf(this->cal[X_AXIS] / this->bed_div_x)) & 1) != 0){  // Odd row
         this->cal[Y_AXIS] -= this->bed_div_y;
-        if (this->cal[Y_AXIS] < 0.0F){
+        if (this->cal[Y_AXIS] < (0.0F - (bed_div_y / 2.0f))){
 
-            THEKERNEL->streams->printf("DEBUG: Y (%f) < cond (%f)\n",this->cal[Y_AXIS], 0.0F);
+            //THEKERNEL->streams->printf("DEBUG: Y (%f) < cond (%f)\n",this->cal[Y_AXIS], 0.0F);
 
             this->cal[X_AXIS] += bed_div_x;
-            if (this->cal[X_AXIS] > this->bed_x){
+            if (this->cal[X_AXIS] > (this->bed_x + (this->bed_div_x / 2.0f))){
                 this->cal[X_AXIS] = 0.0F;
                 this->cal[Y_AXIS] = 0.0F;
             }
@@ -606,12 +612,12 @@ void ZGridStrategy::next_cal(void){
     }
     else {                                          // Even row (0 is an even row - starting point)
         this->cal[Y_AXIS] += bed_div_y;
-      if (this->cal[Y_AXIS] > this->bed_y){
+      if (this->cal[Y_AXIS] > (this->bed_y + (bed_div_y / 2.0f))){
 
-            THEKERNEL->streams->printf("DEBUG: Y (%f) > cond (%f)\n",this->cal[Y_AXIS], this->bed_y);
+            //THEKERNEL->streams->printf("DEBUG: Y (%f) > cond (%f)\n",this->cal[Y_AXIS], this->bed_y);
 
             this->cal[X_AXIS] += bed_div_x;
-            if (this->cal[X_AXIS] > bed_x){
+            if (this->cal[X_AXIS] > (this->bed_x + (this->bed_div_x / 2.0f))){
                 this->cal[X_AXIS] = 0.0F;
                 this->cal[Y_AXIS] = 0.0F;
             }
index 18c07d6..1f72f64 100644 (file)
@@ -258,7 +258,6 @@ void ZProbe::on_gcode_received(void *argument)
         }
 
         if( gcode->g == 30 ) { // simple Z probe
-            gcode->mark_as_taken();
             // first wait for an empty queue i.e. no moves left
             THEKERNEL->conveyor->wait_for_empty_queue();
 
@@ -280,7 +279,6 @@ void ZProbe::on_gcode_received(void *argument)
             // find a strategy to handle the gcode
             for(auto s : strategies){
                 if(s->handleGcode(gcode)) {
-                    gcode->mark_as_taken();
                     return;
                 }
             }
@@ -293,12 +291,10 @@ void ZProbe::on_gcode_received(void *argument)
             int c = this->pin.get();
             gcode->stream->printf(" Probe: %d", c);
             gcode->add_nl = true;
-            gcode->mark_as_taken();
 
         }else {
             for(auto s : strategies){
                 if(s->handleGcode(gcode)) {
-                    gcode->mark_as_taken();
                     return;
                 }
             }
index dbe2fba..6296b7d 100644 (file)
@@ -29,6 +29,7 @@
 #include "PlayerPublicAccess.h"
 #include "TemperatureControlPublicAccess.h"
 #include "TemperatureControlPool.h"
+#include "ExtruderPublicAccess.h"
 
 #include <cstddef>
 #include <cmath>
 #define before_resume_gcode_checksum      CHECKSUM("before_resume_gcode")
 #define leave_heaters_on_suspend_checksum CHECKSUM("leave_heaters_on_suspend")
 
-
-#define extruder_checksum                 CHECKSUM("extruder")
-#define save_state_checksum               CHECKSUM("save_state")
-#define restore_state_checksum            CHECKSUM("restore_state")
-
 extern SDFAT mounter;
 
 Player::Player()
@@ -112,12 +108,10 @@ void Player::on_gcode_received(void *argument)
     string args = get_arguments(gcode->get_command());
     if (gcode->has_m) {
         if (gcode->m == 21) { // Dummy code; makes Octoprint happy -- supposed to initialize SD card
-            gcode->mark_as_taken();
             mounter.remount();
             gcode->stream->printf("SD card ok\r\n");
 
         } else if (gcode->m == 23) { // select file
-            gcode->mark_as_taken();
             this->filename = "/sd/" + args; // filename is whatever is in args
             this->current_stream = &(StreamOutput::NullStream);
 
@@ -149,7 +143,6 @@ void Player::on_gcode_received(void *argument)
             this->elapsed_secs = 0;
 
         } else if (gcode->m == 24) { // start print
-            gcode->mark_as_taken();
             if (this->current_file_handler != NULL) {
                 this->playing_file = true;
                 // this would be a problem if the stream goes away before the file has finished,
@@ -159,11 +152,9 @@ void Player::on_gcode_received(void *argument)
             }
 
         } else if (gcode->m == 25) { // pause print
-            gcode->mark_as_taken();
             this->playing_file = false;
 
         } else if (gcode->m == 26) { // Reset print. Slightly different than M26 in Marlin and the rest
-            gcode->mark_as_taken();
             if(this->current_file_handler != NULL) {
                 string currentfn = this->filename.c_str();
                 unsigned long old_size = this->file_size;
@@ -188,11 +179,9 @@ void Player::on_gcode_received(void *argument)
             }
 
         } else if (gcode->m == 27) { // report print progress, in format used by Marlin
-            gcode->mark_as_taken();
             progress_command("-b", gcode->stream);
 
         } else if (gcode->m == 32) { // select file and start print
-            gcode->mark_as_taken();
             // Get filename
             this->filename = "/sd/" + args; // filename is whatever is in args including spaces
             this->current_stream = &(StreamOutput::NullStream);
index d33b664..e804266 100644 (file)
@@ -35,6 +35,8 @@
 #include "system_LPC17xx.h"
 #include "LPC17xx.h"
 
+#include "mbed.h" // for wait_ms()
+
 extern unsigned int g_maximumHeapAddress;
 
 #include <malloc.h>
@@ -159,17 +161,14 @@ void SimpleShell::on_gcode_received(void *argument)
 
     if (gcode->has_m) {
         if (gcode->m == 20) { // list sd card
-            gcode->mark_as_taken();
             gcode->stream->printf("Begin file list\r\n");
             ls_command("/sd", gcode->stream);
             gcode->stream->printf("End file list\r\n");
 
         } else if (gcode->m == 30) { // remove file
-            gcode->mark_as_taken();
             rm_command("/sd/" + args, gcode->stream);
 
         } else if(gcode->m == 501) { // load config override
-            gcode->mark_as_taken();
             if(args.empty()) {
                 load_command("/sd/config-override", gcode->stream);
             } else {
@@ -177,7 +176,6 @@ void SimpleShell::on_gcode_received(void *argument)
             }
 
         } else if(gcode->m == 504) { // save to specific config override file
-            gcode->mark_as_taken();
             if(args.empty()) {
                 save_command("/sd/config-override", gcode->stream);
             } else {
@@ -447,6 +445,8 @@ void SimpleShell::save_command( string parameters, StreamOutput *stream )
         filename = THEKERNEL->config_override_filename();
     }
 
+    THEKERNEL->conveyor->wait_for_empty_queue(); //just to be safe as it can take a while to run
+
     //remove(filename.c_str()); // seems to cause a hang every now and then
     {
         FileStream fs(filename.c_str());
@@ -454,18 +454,20 @@ void SimpleShell::save_command( string parameters, StreamOutput *stream )
         // this also will truncate the existing file instead of deleting it
     }
 
-    // replace stream with one that writes to config-override file
+    // stream that appends to file
     AppendFileStream *gs = new AppendFileStream(filename.c_str());
     // if(!gs->is_open()) {
     //     stream->printf("Unable to open File %s for write\n", filename.c_str());
     //     return;
     // }
 
+    __disable_irq();
     // issue a M500 which will store values in the file stream
     Gcode *gcode = new Gcode("M500", gs);
     THEKERNEL->call_event(ON_GCODE_RECEIVED, gcode );
     delete gs;
     delete gcode;
+    __enable_irq();
 
     stream->printf("Settings Stored to %s\r\n", filename.c_str());
 }