diff options
42 files changed, 3225 insertions, 2374 deletions
@@ -5,18 +5,18 @@ <storageModule buildSystemId="org.eclipse.cdt.managedbuilder.core.configurationDataProvider" id="it.baeyens.arduino.core.toolChain.release.674980254" moduleId="org.eclipse.cdt.core.settings" name="Release"> <externalSettings/> <extensions> - <extension id="org.eclipse.cdt.core.MakeErrorParser" point="org.eclipse.cdt.core.ErrorParser"/> <extension id="org.eclipse.cdt.core.GCCErrorParser" point="org.eclipse.cdt.core.ErrorParser"/> <extension id="org.eclipse.cdt.core.GLDErrorParser" point="org.eclipse.cdt.core.ErrorParser"/> + <extension id="org.eclipse.cdt.core.MakeErrorParser" point="org.eclipse.cdt.core.ErrorParser"/> <extension id="org.eclipse.cdt.core.ELF" point="org.eclipse.cdt.core.BinaryParser"/> </extensions> </storageModule> <storageModule moduleId="cdtBuildSystem" version="4.0.0"> <configuration artifactName="${ProjName}" buildProperties="" description="" id="it.baeyens.arduino.core.toolChain.release.674980254" name="Release" parent="org.eclipse.cdt.build.core.emptycfg"> <folderInfo id="it.baeyens.arduino.core.toolChain.release.674980254.1794475143" name="/" resourcePath=""> - <toolChain id="it.baeyens.arduino.core.toolChain.release.634866029" name="it.baeyens.arduino.core.toolChain.release" superClass="it.baeyens.arduino.core.toolChain.release"> + <toolChain id="it.baeyens.arduino.core.toolChain.release.634866029" name="it.baeyens.arduino.core.toolChain.release" nonInternalBuilderId="it.baeyens.arduino.sketch.builder" resourceTypeBasedDiscovery="false" superClass="it.baeyens.arduino.core.toolChain.release"> <targetPlatform archList="all" binaryParser="org.eclipse.cdt.core.ELF" id="it.baeyens.arduino.targetplatform.847468288" name="Arduino Target" osList="all" superClass="it.baeyens.arduino.targetplatform"/> - <builder buildPath="${workspace_loc:/RepRapFirmware}/Release" id="it.baeyens.arduino.sketch.builder.455226223" keepEnvironmentInBuildfile="false" managedBuildOn="true" name="Arduino sketch builder" superClass="it.baeyens.arduino.sketch.builder"/> + <builder buildPath="${workspace_loc:/RepRapFirmware}/Release" id="it.baeyens.arduino.sketch.builder.952736646" keepEnvironmentInBuildfile="false" name="Arduino sketch builder" superClass="it.baeyens.arduino.sketch.builder"/> <tool id="it.baeyens.arduino.tool.sketch.compiler.cpp.2087861045" name="Arduino C++ Compiler" superClass="it.baeyens.arduino.tool.sketch.compiler.cpp"> <option id="it.baeyens.arduino.compiler.cpp.sketch.option.incpath.274618772" name="Include Paths (-I)" superClass="it.baeyens.arduino.compiler.cpp.sketch.option.incpath" valueType="includePath"> <listOptionValue builtIn="false" value=""${workspace_loc:/RepRapFirmware/arduino/core}""/> @@ -31,6 +31,7 @@ <listOptionValue builtIn="false" value=""${workspace_loc:/RepRapFirmware/Libraries/Wire}""/> <listOptionValue builtIn="false" value=""${workspace_loc:/RepRapFirmware/Flash}""/> <listOptionValue builtIn="false" value=""${workspace_loc:/RepRapFirmware/arduino/variant}""/> + <listOptionValue builtIn="false" value=""C:\Arduino-1.5.8\hardware\tools\gcc-arm-none-eabi-4.8.3-2014q1\lib\gcc\arm-none-eabi\4.8.3\include""/> </option> <inputType id="it.baeyens.arduino.compiler.cpp.sketch.input.1531738210" name="CPP source files" superClass="it.baeyens.arduino.compiler.cpp.sketch.input"/> </tool> @@ -47,6 +48,7 @@ <listOptionValue builtIn="false" value=""${workspace_loc:/RepRapFirmware/Libraries/SD_HSMCI/utility}""/> <listOptionValue builtIn="false" value=""${workspace_loc:/RepRapFirmware/Libraries/Wire}""/> <listOptionValue builtIn="false" value=""${workspace_loc:/RepRapFirmware/arduino/variant}""/> + <listOptionValue builtIn="false" value=""C:\Arduino-1.5.8\hardware\tools\gcc-arm-none-eabi-4.8.3-2014q1\arm-none-eabi\include""/> </option> <inputType id="it.baeyens.arduino.compiler.c.sketch.input.1546791595" name="C Source Files" superClass="it.baeyens.arduino.compiler.c.sketch.input"/> </tool> @@ -68,9 +70,6 @@ <storageModule moduleId="cdtBuildSystem" version="4.0.0"> <project id="RepRapFirmware.null.1049349308" name="RepRapFirmware"/> </storageModule> - <storageModule moduleId="scannerConfiguration"> - <autodiscovery enabled="true" problemReportingEnabled="true" selectedProfileId=""/> - </storageModule> <storageModule moduleId="org.eclipse.cdt.core.LanguageSettingsProviders"/> <storageModule moduleId="refreshScope" versionNumber="2"> <configuration configurationName="Release"> @@ -78,4 +77,11 @@ </configuration> </storageModule> <storageModule moduleId="org.eclipse.cdt.make.core.buildtargets"/> + <storageModule moduleId="org.eclipse.cdt.internal.ui.text.commentOwnerProjectMappings"/> + <storageModule moduleId="scannerConfiguration"> + <autodiscovery enabled="true" problemReportingEnabled="true" selectedProfileId=""/> + <scannerConfigBuildInfo instanceId="it.baeyens.arduino.core.toolChain.release.674980254"> + <autodiscovery enabled="true" problemReportingEnabled="true" selectedProfileId=""/> + </scannerConfigBuildInfo> + </storageModule> </cproject> diff --git a/.settings/language.settings.xml b/.settings/language.settings.xml index 16d0fb79..0176319d 100644 --- a/.settings/language.settings.xml +++ b/.settings/language.settings.xml @@ -2,12 +2,11 @@ <project> <configuration id="it.baeyens.arduino.core.toolChain.release.674980254" name="Release"> <extension point="org.eclipse.cdt.core.LanguageSettingsProvider"> - <provider copy-of="extension" id="org.eclipse.cdt.ui.UserLanguageSettingsProvider"/> - <provider-reference id="org.eclipse.cdt.managedbuilder.core.MBSLanguageSettingsProvider" ref="shared-provider"/> <provider class="it.baeyens.arduino.toolchain.ArduinoLanguageProvider" console="false" id="it.baeyens.arduino.languageSettingsProvider" keep-relative-paths="false" name="Arduino Compiler Settings" parameter="${COMMAND} -E -P -v -dD ${INPUTS}" prefer-non-shared="true"> <language-scope id="org.eclipse.cdt.core.gcc"/> <language-scope id="org.eclipse.cdt.core.g++"/> </provider> + <provider-reference id="org.eclipse.cdt.managedbuilder.core.MBSLanguageSettingsProvider" ref="shared-provider"/> </extension> </configuration> </project> diff --git a/.settings/org.eclipse.cdt.core.prefs b/.settings/org.eclipse.cdt.core.prefs index 95df602b..d4474108 100644 --- a/.settings/org.eclipse.cdt.core.prefs +++ b/.settings/org.eclipse.cdt.core.prefs @@ -37,13 +37,13 @@ environment/project/it.baeyens.arduino.core.toolChain.release.674980254/A.BUILD. environment/project/it.baeyens.arduino.core.toolChain.release.674980254/A.BUILD.SYSTEM.PATH/value=${A.RUNTIME.IDE.PATH}/hardware/arduino/sam/system environment/project/it.baeyens.arduino.core.toolChain.release.674980254/A.BUILD.USB_FLAGS/delimiter=; environment/project/it.baeyens.arduino.core.toolChain.release.674980254/A.BUILD.USB_FLAGS/operation=replace -environment/project/it.baeyens.arduino.core.toolChain.release.674980254/A.BUILD.USB_FLAGS/value=-DUSB_VID\=${A.BUILD.VID} -DUSB_PID\=${A.BUILD.PID} -DUSBCON "-DUSB_MANUFACTURER\=${A.BUILD.USB_MANUFACTURER}" "-DUSB_PRODUCT\=\\"${A.BUILD.USB_PRODUCT}\\"" +environment/project/it.baeyens.arduino.core.toolChain.release.674980254/A.BUILD.USB_FLAGS/value=-DUSB_VID\=${A.BUILD.VID} -DUSB_PID\=${A.BUILD.PID} -DUSBCON environment/project/it.baeyens.arduino.core.toolChain.release.674980254/A.BUILD.USB_MANUFACTURER/delimiter=; environment/project/it.baeyens.arduino.core.toolChain.release.674980254/A.BUILD.USB_MANUFACTURER/operation=replace -environment/project/it.baeyens.arduino.core.toolChain.release.674980254/A.BUILD.USB_MANUFACTURER/value=Unknown +environment/project/it.baeyens.arduino.core.toolChain.release.674980254/A.BUILD.USB_MANUFACTURER/value="Unknown" environment/project/it.baeyens.arduino.core.toolChain.release.674980254/A.BUILD.USB_PRODUCT/delimiter=; environment/project/it.baeyens.arduino.core.toolChain.release.674980254/A.BUILD.USB_PRODUCT/operation=replace -environment/project/it.baeyens.arduino.core.toolChain.release.674980254/A.BUILD.USB_PRODUCT/value=Arduino Due +environment/project/it.baeyens.arduino.core.toolChain.release.674980254/A.BUILD.USB_PRODUCT/value="Arduino Due" environment/project/it.baeyens.arduino.core.toolChain.release.674980254/A.BUILD.USE_ARCHIVER/delimiter=; environment/project/it.baeyens.arduino.core.toolChain.release.674980254/A.BUILD.USE_ARCHIVER/operation=replace environment/project/it.baeyens.arduino.core.toolChain.release.674980254/A.BUILD.USE_ARCHIVER/value=true @@ -85,13 +85,13 @@ environment/project/it.baeyens.arduino.core.toolChain.release.674980254/A.COMPIL environment/project/it.baeyens.arduino.core.toolChain.release.674980254/A.COMPILER.C.ELF.EXTRA_FLAGS/value= environment/project/it.baeyens.arduino.core.toolChain.release.674980254/A.COMPILER.C.ELF.FLAGS/delimiter=; environment/project/it.baeyens.arduino.core.toolChain.release.674980254/A.COMPILER.C.ELF.FLAGS/operation=replace -environment/project/it.baeyens.arduino.core.toolChain.release.674980254/A.COMPILER.C.ELF.FLAGS/value=-O2 -Wl,--gc-sections +environment/project/it.baeyens.arduino.core.toolChain.release.674980254/A.COMPILER.C.ELF.FLAGS/value=-Os -Wl,--gc-sections environment/project/it.baeyens.arduino.core.toolChain.release.674980254/A.COMPILER.C.EXTRA_FLAGS/delimiter=; environment/project/it.baeyens.arduino.core.toolChain.release.674980254/A.COMPILER.C.EXTRA_FLAGS/operation=replace environment/project/it.baeyens.arduino.core.toolChain.release.674980254/A.COMPILER.C.EXTRA_FLAGS/value= environment/project/it.baeyens.arduino.core.toolChain.release.674980254/A.COMPILER.C.FLAGS/delimiter=; environment/project/it.baeyens.arduino.core.toolChain.release.674980254/A.COMPILER.C.FLAGS/operation=replace -environment/project/it.baeyens.arduino.core.toolChain.release.674980254/A.COMPILER.C.FLAGS/value=-c -g -O2 -w -ffunction-sections -fdata-sections -nostdlib --param max-inline-insns-single\=500 -Dprintf\=iprintf +environment/project/it.baeyens.arduino.core.toolChain.release.674980254/A.COMPILER.C.FLAGS/value=-c -g -Os -w -ffunction-sections -fdata-sections -nostdlib --param max-inline-insns-single\=500 -Dprintf\=iprintf environment/project/it.baeyens.arduino.core.toolChain.release.674980254/A.COMPILER.CPP.CMD/delimiter=; environment/project/it.baeyens.arduino.core.toolChain.release.674980254/A.COMPILER.CPP.CMD/operation=replace environment/project/it.baeyens.arduino.core.toolChain.release.674980254/A.COMPILER.CPP.CMD/value=arm-none-eabi-g++ @@ -100,7 +100,7 @@ environment/project/it.baeyens.arduino.core.toolChain.release.674980254/A.COMPIL environment/project/it.baeyens.arduino.core.toolChain.release.674980254/A.COMPILER.CPP.EXTRA_FLAGS/value= environment/project/it.baeyens.arduino.core.toolChain.release.674980254/A.COMPILER.CPP.FLAGS/delimiter=; environment/project/it.baeyens.arduino.core.toolChain.release.674980254/A.COMPILER.CPP.FLAGS/operation=replace -environment/project/it.baeyens.arduino.core.toolChain.release.674980254/A.COMPILER.CPP.FLAGS/value=-c -g -std\=gnu++11 -O2 -w -ffunction-sections -fdata-sections -nostdlib -fno-threadsafe-statics --param max-inline-insns-single\=500 -fno-rtti -fno-exceptions -Dprintf\=iprintf +environment/project/it.baeyens.arduino.core.toolChain.release.674980254/A.COMPILER.CPP.FLAGS/value=-c -g -Os -w -ffunction-sections -fdata-sections -nostdlib -fno-threadsafe-statics --param max-inline-insns-single\=500 -fno-rtti -fno-exceptions -Dprintf\=iprintf environment/project/it.baeyens.arduino.core.toolChain.release.674980254/A.COMPILER.DEFINE/delimiter=; environment/project/it.baeyens.arduino.core.toolChain.release.674980254/A.COMPILER.DEFINE/operation=replace environment/project/it.baeyens.arduino.core.toolChain.release.674980254/A.COMPILER.DEFINE/value=-DARDUINO\= @@ -274,10 +274,10 @@ environment/project/it.baeyens.arduino.core.toolChain.release.674980254/JANTJE.E environment/project/it.baeyens.arduino.core.toolChain.release.674980254/JANTJE.EXTRA.C.COMPILE/value= environment/project/it.baeyens.arduino.core.toolChain.release.674980254/JANTJE.EXTRA.COMPILE/delimiter=; environment/project/it.baeyens.arduino.core.toolChain.release.674980254/JANTJE.EXTRA.COMPILE/operation=replace -environment/project/it.baeyens.arduino.core.toolChain.release.674980254/JANTJE.EXTRA.COMPILE/value= +environment/project/it.baeyens.arduino.core.toolChain.release.674980254/JANTJE.EXTRA.COMPILE/value=-O2 environment/project/it.baeyens.arduino.core.toolChain.release.674980254/JANTJE.EXTRA.CPP.COMPILE/delimiter=; environment/project/it.baeyens.arduino.core.toolChain.release.674980254/JANTJE.EXTRA.CPP.COMPILE/operation=replace -environment/project/it.baeyens.arduino.core.toolChain.release.674980254/JANTJE.EXTRA.CPP.COMPILE/value= +environment/project/it.baeyens.arduino.core.toolChain.release.674980254/JANTJE.EXTRA.CPP.COMPILE/value=-std\=gnu++11 environment/project/it.baeyens.arduino.core.toolChain.release.674980254/JANTJE.PLATFORM_FILE/delimiter=; environment/project/it.baeyens.arduino.core.toolChain.release.674980254/JANTJE.PLATFORM_FILE/operation=replace environment/project/it.baeyens.arduino.core.toolChain.release.674980254/JANTJE.PLATFORM_FILE/value=C\:/Arduino-1.5.8/hardware/arduino/sam/platform.txt diff --git a/ArduinoCorePatches/sam/arduino_due_x/variant.cpp b/ArduinoCorePatches/sam/arduino_due_x/variant.cpp deleted file mode 100644 index 35e79ddc..00000000 --- a/ArduinoCorePatches/sam/arduino_due_x/variant.cpp +++ /dev/null @@ -1,450 +0,0 @@ -/* - Copyright (c) 2011 Arduino. All right reserved. - - This library is free software; you can redistribute it and/or - modify it under the terms of the GNU Lesser General Public - License as published by the Free Software Foundation; either - version 2.1 of the License, or (at your option) any later version. - - This library is distributed in the hope that it will be useful, - but WITHOUT ANY WARRANTY; without even the implied warranty of - MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. - See the GNU Lesser General Public License for more details. - - You should have received a copy of the GNU Lesser General Public - License along with this library; if not, write to the Free Software - Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA -*/ - -#include "variant.h" - -/* - * DUE Board pin | PORT | Label - * ----------------+--------+------- - * 0 | PA8 | "RX0" - * 1 | PA9 | "TX0" - * 2 TIOA0 | PB25 | - * 3 TIOA7 | PC28 | - * 4 NPCS1 | PA29 | - * TIOB6 | PC26 | - * 5 TIOA6 | PC25 | - * 6 PWML7 | PC24 | - * 7 PWML6 | PC23 | - * 8 PWML5 | PC22 | - * 9 PWML4 | PC21 | - * 10 NPCS0 | PA28 | - * TIOB7 | PC29 | - * 11 TIOA8 | PD7 | - * 12 TIOB8 | PD8 | - * 13 TIOB0 | PB27 | LED AMBER "L" - * 14 TXD3 | PD4 | "TX3" - * 15 RXD3 | PD5 | "RX3" - * 16 TXD1 | PA13 | "TX2" - * 17 RXD1 | PA12 | "RX2" - * 18 TXD0 | PA11 | "TX1" - * 19 RXD0 | PA10 | "RX1" - * 20 | PB12 | "SDA" - * 21 | PB13 | "SCL" - * 22 | PB26 | - * 23 | PA14 | - * 24 | PA15 | - * 25 | PD0 | - * 26 | PD1 | - * 27 | PD2 | - * 28 | PD3 | - * 29 | PD6 | - * 30 | PD9 | - * 31 | PA7 | - * 32 | PD10 | - * 33 | PC1 | - * 34 | PC2 | - * 35 | PC3 | - * 36 | PC4 | - * 37 | PC5 | - * 38 | PC6 | - * 39 | PC7 | - * 40 | PC8 | - * 41 | PC9 | - * 42 | PA19 | - * 43 | PA20 | - * 44 | PC19 | - * 45 | PC18 | - * 46 | PC17 | - * 47 | PC16 | - * 48 | PC15 | - * 49 | PC14 | - * 50 | PC13 | - * 51 | PC12 | - * 52 NPCS2 | PB21 | - * 53 | PB14 | - * 54 | PA16 | "A0" - * 55 | PA24 | "A1" - * 56 | PA23 | "A2" - * 57 | PA22 | "A3" - * 58 TIOB2 | PA6 | "A4" - * 69 | PA4 | "A5" - * 60 TIOB1 | PA3 | "A6" - * 61 TIOA1 | PA2 | "A7" - * 62 | PB17 | "A8" - * 63 | PB18 | "A9" - * 64 | PB19 | "A10" - * 65 | PB20 | "A11" - * 66 | PB15 | "DAC0" - * 67 | PB16 | "DAC1" - * 68 | PA1 | "CANRX" - * 69 | PA0 | "CANTX" - * 70 | PA17 | "SDA1" - * 71 | PA18 | "SCL1" - * 72 | PC30 | LED AMBER "RX" - * 73 | PA21 | LED AMBER "TX" - * 74 MISO | PA25 | - * 75 MOSI | PA26 | - * 76 SCLK | PA27 | - * 77 NPCS0 | PA28 | - * 78 NPCS3 | PB23 | unconnected! - * - * USB pin | PORT - * ----------------+-------- - * ID | PB11 - * VBOF | PB10 - * - */ - -#ifdef __cplusplus -extern "C" { -#endif - -/* - * Pins descriptions - */ -extern const PinDescription g_APinDescription[]= -{ - // 0 .. 53 - Digital pins - // ---------------------- - // 0/1 - UART (Serial) - { PIOA, PIO_PA8A_URXD, ID_PIOA, PIO_PERIPH_A, PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // URXD - { PIOA, PIO_PA9A_UTXD, ID_PIOA, PIO_PERIPH_A, PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // UTXD - - // 2 - { PIOB, PIO_PB25B_TIOA0, ID_PIOB, PIO_PERIPH_B, PIO_DEFAULT, (PIN_ATTR_DIGITAL|PIN_ATTR_TIMER), NO_ADC, NO_ADC, NOT_ON_PWM, TC0_CHA0 }, // TIOA0 - { PIOC, PIO_PC28B_TIOA7, ID_PIOC, PIO_PERIPH_B, PIO_DEFAULT, (PIN_ATTR_DIGITAL|PIN_ATTR_TIMER), NO_ADC, NO_ADC, NOT_ON_PWM, TC2_CHA7 }, // TIOA7 - { PIOC, PIO_PC26B_TIOB6, ID_PIOC, PIO_PERIPH_B, PIO_DEFAULT, (PIN_ATTR_DIGITAL|PIN_ATTR_TIMER), NO_ADC, NO_ADC, NOT_ON_PWM, TC2_CHB6 }, // TIOB6 - - // 5 - { PIOC, PIO_PC25B_TIOA6, ID_PIOC, PIO_PERIPH_B, PIO_DEFAULT, (PIN_ATTR_DIGITAL|PIN_ATTR_TIMER), NO_ADC, NO_ADC, NOT_ON_PWM, TC2_CHA6 }, // TIOA6 - { PIOC, PIO_PC24B_PWML7, ID_PIOC, PIO_PERIPH_B, PIO_DEFAULT, (PIN_ATTR_DIGITAL|PIN_ATTR_PWM), NO_ADC, NO_ADC, PWM_CH7, NOT_ON_TIMER }, // PWML7 - { PIOC, PIO_PC23B_PWML6, ID_PIOC, PIO_PERIPH_B, PIO_DEFAULT, (PIN_ATTR_DIGITAL|PIN_ATTR_PWM), NO_ADC, NO_ADC, PWM_CH6, NOT_ON_TIMER }, // PWML6 - { PIOC, PIO_PC22B_PWML5, ID_PIOC, PIO_PERIPH_B, PIO_DEFAULT, (PIN_ATTR_DIGITAL|PIN_ATTR_PWM), NO_ADC, NO_ADC, PWM_CH5, NOT_ON_TIMER }, // PWML5 - { PIOC, PIO_PC21B_PWML4, ID_PIOC, PIO_PERIPH_B, PIO_DEFAULT, (PIN_ATTR_DIGITAL|PIN_ATTR_PWM), NO_ADC, NO_ADC, PWM_CH4, NOT_ON_TIMER }, // PWML4 - // 10 - { PIOC, PIO_PC29B_TIOB7, ID_PIOC, PIO_PERIPH_B, PIO_DEFAULT, (PIN_ATTR_DIGITAL|PIN_ATTR_TIMER), NO_ADC, NO_ADC, NOT_ON_PWM, TC2_CHB7 }, // TIOB7 - { PIOD, PIO_PD7B_TIOA8, ID_PIOD, PIO_PERIPH_B, PIO_DEFAULT, (PIN_ATTR_DIGITAL|PIN_ATTR_TIMER), NO_ADC, NO_ADC, NOT_ON_PWM, TC2_CHA8 }, // TIOA8 - { PIOD, PIO_PD8B_TIOB8, ID_PIOD, PIO_PERIPH_B, PIO_DEFAULT, (PIN_ATTR_DIGITAL|PIN_ATTR_TIMER), NO_ADC, NO_ADC, NOT_ON_PWM, TC2_CHB8 }, // TIOB8 - - // 13 - AMBER LED - { PIOB, PIO_PB27B_TIOB0, ID_PIOB, PIO_PERIPH_B, PIO_DEFAULT, (PIN_ATTR_DIGITAL|PIN_ATTR_TIMER), NO_ADC, NO_ADC, NOT_ON_PWM, TC0_CHB0 }, // TIOB0 - - // 14/15 - USART3 (Serial3) - { PIOD, PIO_PD4B_TXD3, ID_PIOD, PIO_PERIPH_B, PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // TXD3 - { PIOD, PIO_PD5B_RXD3, ID_PIOD, PIO_PERIPH_B, PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // RXD3 - - // 16/17 - USART1 (Serial2) - { PIOA, PIO_PA13A_TXD1, ID_PIOA, PIO_PERIPH_A, PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // TXD1 - { PIOA, PIO_PA12A_RXD1, ID_PIOA, PIO_PERIPH_A, PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // RXD1 - - // 18/19 - USART0 (Serial1) - { PIOA, PIO_PA11A_TXD0, ID_PIOA, PIO_PERIPH_A, PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // TXD0 - { PIOA, PIO_PA10A_RXD0, ID_PIOA, PIO_PERIPH_A, PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // RXD0 - - // 20/21 - TWI1 - { PIOB, PIO_PB12A_TWD1, ID_PIOB, PIO_PERIPH_A, PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // TWD1 - SDA0 - { PIOB, PIO_PB13A_TWCK1, ID_PIOB, PIO_PERIPH_A, PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // TWCK1 - SCL0 - - // 22 - { PIOB, PIO_PB26, ID_PIOB, PIO_OUTPUT_0, PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // PIN 22 - { PIOA, PIO_PA14, ID_PIOA, PIO_OUTPUT_0, PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // PIN 23 - { PIOA, PIO_PA15, ID_PIOA, PIO_OUTPUT_0, PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // PIN 24 - { PIOD, PIO_PD0, ID_PIOD, PIO_OUTPUT_0, PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // PIN 25 - - // 26 - { PIOD, PIO_PD1, ID_PIOD, PIO_OUTPUT_0, PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // PIN 26 - { PIOD, PIO_PD2, ID_PIOD, PIO_OUTPUT_0, PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // PIN 27 - { PIOD, PIO_PD3, ID_PIOD, PIO_OUTPUT_0, PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // PIN 28 - { PIOD, PIO_PD6, ID_PIOD, PIO_OUTPUT_0, PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // PIN 29 - - // 30 - { PIOD, PIO_PD9, ID_PIOD, PIO_OUTPUT_0, PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // PIN 30 - { PIOA, PIO_PA7, ID_PIOA, PIO_OUTPUT_0, PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // PIN 31 - { PIOD, PIO_PD10, ID_PIOD, PIO_OUTPUT_0, PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // PIN 32 - { PIOC, PIO_PC1, ID_PIOC, PIO_OUTPUT_0, PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // PIN 33 - - // 34 - { PIOC, PIO_PC2, ID_PIOC, PIO_OUTPUT_0, PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // PIN 34 - { PIOC, PIO_PC3, ID_PIOC, PIO_OUTPUT_0, PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // PIN 35 - { PIOC, PIO_PC4, ID_PIOC, PIO_OUTPUT_0, PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // PIN 36 - { PIOC, PIO_PC5, ID_PIOC, PIO_OUTPUT_0, PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // PIN 37 - - // 38 - { PIOC, PIO_PC6, ID_PIOC, PIO_OUTPUT_0, PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // PIN 38 - { PIOC, PIO_PC7, ID_PIOC, PIO_OUTPUT_0, PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // PIN 39 - { PIOC, PIO_PC8, ID_PIOC, PIO_OUTPUT_0, PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // PIN 40 - { PIOC, PIO_PC9, ID_PIOC, PIO_OUTPUT_0, PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // PIN 41 - - // 42 - { PIOA, PIO_PA19, ID_PIOA, PIO_OUTPUT_0, PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // PIN 42 - { PIOA, PIO_PA20, ID_PIOA, PIO_OUTPUT_0, PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // PIN 43 - { PIOC, PIO_PC19, ID_PIOC, PIO_OUTPUT_0, PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // PIN 44 - { PIOC, PIO_PC18, ID_PIOC, PIO_OUTPUT_0, PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // PIN 45 - - // 46 - { PIOC, PIO_PC17, ID_PIOC, PIO_OUTPUT_0, PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // PIN 46 - { PIOC, PIO_PC16, ID_PIOC, PIO_OUTPUT_0, PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // PIN 47 - { PIOC, PIO_PC15, ID_PIOC, PIO_OUTPUT_0, PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // PIN 48 - { PIOC, PIO_PC14, ID_PIOC, PIO_OUTPUT_0, PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // PIN 49 - - // 50 - { PIOC, PIO_PC13, ID_PIOC, PIO_OUTPUT_0, PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // PIN 50 - { PIOC, PIO_PC12, ID_PIOC, PIO_OUTPUT_0, PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // PIN 51 - { PIOB, PIO_PB21, ID_PIOB, PIO_OUTPUT_0, PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // PIN 52 - { PIOB, PIO_PB14, ID_PIOB, PIO_OUTPUT_0, PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // PIN 53 - - - // 54 .. 65 - Analog pins - // ---------------------- - { PIOA, PIO_PA16X1_AD7, ID_PIOA, PIO_INPUT, PIO_DEFAULT, PIN_ATTR_ANALOG, ADC0, ADC7, NOT_ON_PWM, NOT_ON_TIMER }, // AD0 - { PIOA, PIO_PA24X1_AD6, ID_PIOA, PIO_INPUT, PIO_DEFAULT, PIN_ATTR_ANALOG, ADC1, ADC6, NOT_ON_PWM, NOT_ON_TIMER }, // AD1 - { PIOA, PIO_PA23X1_AD5, ID_PIOA, PIO_INPUT, PIO_DEFAULT, PIN_ATTR_ANALOG, ADC2, ADC5, NOT_ON_PWM, NOT_ON_TIMER }, // AD2 - { PIOA, PIO_PA22X1_AD4, ID_PIOA, PIO_INPUT, PIO_DEFAULT, PIN_ATTR_ANALOG, ADC3, ADC4, NOT_ON_PWM, NOT_ON_TIMER }, // AD3 - // 58 - { PIOA, PIO_PA6X1_AD3, ID_PIOA, PIO_INPUT, PIO_DEFAULT, PIN_ATTR_ANALOG, ADC4, ADC3, NOT_ON_PWM, TC0_CHB2 }, // AD4 - { PIOA, PIO_PA4X1_AD2, ID_PIOA, PIO_INPUT, PIO_DEFAULT, PIN_ATTR_ANALOG, ADC5, ADC2, NOT_ON_PWM, NOT_ON_TIMER }, // AD5 - { PIOA, PIO_PA3X1_AD1, ID_PIOA, PIO_INPUT, PIO_DEFAULT, PIN_ATTR_ANALOG, ADC6, ADC1, NOT_ON_PWM, TC0_CHB1 }, // AD6 - { PIOA, PIO_PA2X1_AD0, ID_PIOA, PIO_INPUT, PIO_DEFAULT, PIN_ATTR_ANALOG, ADC7, ADC0, NOT_ON_PWM, TC0_CHA1 }, // AD7 - // 62 - { PIOB, PIO_PB17X1_AD10, ID_PIOB, PIO_INPUT, PIO_DEFAULT, PIN_ATTR_ANALOG, ADC8, ADC10, NOT_ON_PWM, NOT_ON_TIMER }, // AD8 - { PIOB, PIO_PB18X1_AD11, ID_PIOB, PIO_INPUT, PIO_DEFAULT, PIN_ATTR_ANALOG, ADC9, ADC11, NOT_ON_PWM, NOT_ON_TIMER }, // AD9 - { PIOB, PIO_PB19X1_AD12, ID_PIOB, PIO_INPUT, PIO_DEFAULT, PIN_ATTR_ANALOG, ADC10, ADC12, NOT_ON_PWM, NOT_ON_TIMER }, // AD10 - { PIOB, PIO_PB20X1_AD13, ID_PIOB, PIO_INPUT, PIO_DEFAULT, PIN_ATTR_ANALOG, ADC11, ADC13, NOT_ON_PWM, NOT_ON_TIMER }, // AD11 - - // 66/67 - DAC0/DAC1 - { PIOB, PIO_PB15X1_DAC0, ID_PIOB, PIO_INPUT, PIO_DEFAULT, PIN_ATTR_ANALOG, ADC12, DA0, NOT_ON_PWM, NOT_ON_TIMER }, // DAC0 - { PIOB, PIO_PB16X1_DAC1, ID_PIOB, PIO_INPUT, PIO_DEFAULT, PIN_ATTR_ANALOG, ADC13, DA1, NOT_ON_PWM, NOT_ON_TIMER }, // DAC1 - - // 68/69 - CANRX0/CANTX0 - { PIOA, PIO_PA1A_CANRX0, ID_PIOA, PIO_PERIPH_A, PIO_DEFAULT, PIN_ATTR_DIGITAL, ADC14, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // CANRX - { PIOA, PIO_PA0A_CANTX0, ID_PIOA, PIO_PERIPH_A, PIO_DEFAULT, PIN_ATTR_DIGITAL, ADC15, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // CANTX - - // 70/71 - TWI0 - { PIOA, PIO_PA17A_TWD0, ID_PIOA, PIO_PERIPH_A, PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // TWD0 - SDA1 - { PIOA, PIO_PA18A_TWCK0, ID_PIOA, PIO_PERIPH_A, PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // TWCK0 - SCL1 - - // 72/73 - LEDs - { PIOC, PIO_PC30, ID_PIOC, PIO_OUTPUT_0, PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // LED AMBER RXL - { PIOA, PIO_PA21, ID_PIOA, PIO_OUTPUT_0, PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // LED AMBER TXL - - // 74/75/76 - SPI - { PIOA, PIO_PA25A_SPI0_MISO,ID_PIOA,PIO_PERIPH_A, PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // MISO - { PIOA, PIO_PA26A_SPI0_MOSI,ID_PIOA,PIO_PERIPH_A, PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // MOSI - { PIOA, PIO_PA27A_SPI0_SPCK,ID_PIOA,PIO_PERIPH_A, PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // SPCK - - // 77 - SPI CS0 - { PIOA, PIO_PA28A_SPI0_NPCS0,ID_PIOA,PIO_PERIPH_A,PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // NPCS0 - - // 78 - SPI CS3 (unconnected) - { PIOB, PIO_PB23B_SPI0_NPCS3,ID_PIOB,PIO_PERIPH_B,PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // NPCS3 - - // 79 .. 84 - "All pins" masks - - // 79 - TWI0 all pins - { PIOA, PIO_PA17A_TWD0|PIO_PA18A_TWCK0, ID_PIOA, PIO_PERIPH_A, PIO_DEFAULT, (PIN_ATTR_DIGITAL|PIN_ATTR_COMBO), NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, - // 80 - TWI1 all pins - { PIOB, PIO_PB12A_TWD1|PIO_PB13A_TWCK1, ID_PIOB, PIO_PERIPH_A, PIO_DEFAULT, (PIN_ATTR_DIGITAL|PIN_ATTR_COMBO), NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, - // 81 - UART (Serial) all pins - { PIOA, PIO_PA8A_URXD|PIO_PA9A_UTXD, ID_PIOA, PIO_PERIPH_A, PIO_DEFAULT, (PIN_ATTR_DIGITAL|PIN_ATTR_COMBO), NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, - // 82 - USART0 (Serial1) all pins - { PIOA, PIO_PA11A_TXD0|PIO_PA10A_RXD0, ID_PIOA, PIO_PERIPH_A, PIO_DEFAULT, (PIN_ATTR_DIGITAL|PIN_ATTR_COMBO), NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, - // 83 - USART1 (Serial2) all pins - { PIOA, PIO_PA13A_TXD1|PIO_PA12A_RXD1, ID_PIOA, PIO_PERIPH_A, PIO_DEFAULT, (PIN_ATTR_DIGITAL|PIN_ATTR_COMBO), NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, - // 84 - USART3 (Serial3) all pins - { PIOD, PIO_PD4B_TXD3|PIO_PD5B_RXD3, ID_PIOD, PIO_PERIPH_B, PIO_DEFAULT, (PIN_ATTR_DIGITAL|PIN_ATTR_COMBO), NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, - - // 85 - USB - { PIOB, PIO_PB11A_UOTGID|PIO_PB10A_UOTGVBOF, ID_PIOB, PIO_PERIPH_A, PIO_DEFAULT, PIN_ATTR_DIGITAL,NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // ID - VBOF - - // 86 - SPI CS2 - { PIOB, PIO_PB21B_SPI0_NPCS2, ID_PIOB, PIO_PERIPH_B, PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // NPCS2 - - // 87 - SPI CS1 - { PIOA, PIO_PA29A_SPI0_NPCS1, ID_PIOA, PIO_PERIPH_A, PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // NPCS1 - - // 88/89 - CANRX1/CANTX1 (same physical pin for 66/53) - { PIOB, PIO_PB15A_CANRX1, ID_PIOB, PIO_PERIPH_A, PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // CANRX1 - { PIOB, PIO_PB14A_CANTX1, ID_PIOB, PIO_PERIPH_A, PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // CANTX1 - - // 90 .. 91 - "All CAN pins" masks - // 90 - CAN0 all pins - { PIOA, PIO_PA1A_CANRX0|PIO_PA0A_CANTX0, ID_PIOA, PIO_PERIPH_A, PIO_DEFAULT, (PIN_ATTR_DIGITAL|PIN_ATTR_COMBO), NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, - // 91 - CAN1 all pins - { PIOB, PIO_PB15A_CANRX1|PIO_PB14A_CANTX1, ID_PIOB, PIO_PERIPH_A, PIO_DEFAULT, (PIN_ATTR_DIGITAL|PIN_ATTR_COMBO), NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, - - // END - { NULL, 0, 0, PIO_NOT_A_PIN, PIO_DEFAULT, 0, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER } -} ; - -#ifdef __cplusplus -} -#endif - -/* - * UART objects - */ -RingBuffer rx_buffer1; - -UARTClass Serial(UART, UART_IRQn, ID_UART, &rx_buffer1); -void serialEvent() __attribute__((weak)); -void serialEvent() { } - -// IT handlers -void UART_Handler(void) -{ - Serial.IrqHandler(); -} - -// ---------------------------------------------------------------------------- -/* - * USART objects - */ -RingBuffer rx_buffer2; -RingBuffer rx_buffer3; -RingBuffer rx_buffer4; - -USARTClass Serial1(USART0, USART0_IRQn, ID_USART0, &rx_buffer2); -void serialEvent1() __attribute__((weak)); -void serialEvent1() { } -USARTClass Serial2(USART1, USART1_IRQn, ID_USART1, &rx_buffer3); -void serialEvent2() __attribute__((weak)); -void serialEvent2() { } -USARTClass Serial3(USART3, USART3_IRQn, ID_USART3, &rx_buffer4); -void serialEvent3() __attribute__((weak)); -void serialEvent3() { } - -// IT handlers -void USART0_Handler(void) -{ - Serial1.IrqHandler(); -} - -void USART1_Handler(void) -{ - Serial2.IrqHandler(); -} - -void USART3_Handler(void) -{ - Serial3.IrqHandler(); -} - -// ---------------------------------------------------------------------------- - -void serialEventRun(void) -{ - if (Serial.available()) serialEvent(); - if (Serial1.available()) serialEvent1(); - if (Serial2.available()) serialEvent2(); - if (Serial3.available()) serialEvent3(); -} - -// ---------------------------------------------------------------------------- - -#ifdef __cplusplus -extern "C" { -#endif - -void __libc_init_array(void); - -void init( void ) -{ - SystemInit(); - - // Set Systick to 1ms interval, common to all SAM3 variants - if (SysTick_Config(SystemCoreClock / 1000)) - { - // Capture error - while (true); - } - - // Disable watchdog - //***** Commented out by DC42 so we can use the watchdog in the Duet firmware - //WDT_Disable(WDT); - - // Initialize C library - __libc_init_array(); - - // Disable pull-up on every pin - for (unsigned i = 0; i < PINS_COUNT; i++) - digitalWrite(i, LOW); - - // Enable parallel access on PIO output data registers - PIOA->PIO_OWER = 0xFFFFFFFF; - PIOB->PIO_OWER = 0xFFFFFFFF; - PIOC->PIO_OWER = 0xFFFFFFFF; - PIOD->PIO_OWER = 0xFFFFFFFF; - - // Initialize Serial port U(S)ART pins - PIO_Configure( - g_APinDescription[PINS_UART].pPort, - g_APinDescription[PINS_UART].ulPinType, - g_APinDescription[PINS_UART].ulPin, - g_APinDescription[PINS_UART].ulPinConfiguration); - digitalWrite(0, HIGH); // Enable pullup for RX0 - PIO_Configure( - g_APinDescription[PINS_USART0].pPort, - g_APinDescription[PINS_USART0].ulPinType, - g_APinDescription[PINS_USART0].ulPin, - g_APinDescription[PINS_USART0].ulPinConfiguration); - PIO_Configure( - g_APinDescription[PINS_USART1].pPort, - g_APinDescription[PINS_USART1].ulPinType, - g_APinDescription[PINS_USART1].ulPin, - g_APinDescription[PINS_USART1].ulPinConfiguration); - PIO_Configure( - g_APinDescription[PINS_USART3].pPort, - g_APinDescription[PINS_USART3].ulPinType, - g_APinDescription[PINS_USART3].ulPin, - g_APinDescription[PINS_USART3].ulPinConfiguration); - - // Initialize USB pins - PIO_Configure( - g_APinDescription[PINS_USB].pPort, - g_APinDescription[PINS_USB].ulPinType, - g_APinDescription[PINS_USB].ulPin, - g_APinDescription[PINS_USB].ulPinConfiguration); - - // Initialize CAN pins - PIO_Configure( - g_APinDescription[PINS_CAN0].pPort, - g_APinDescription[PINS_CAN0].ulPinType, - g_APinDescription[PINS_CAN0].ulPin, - g_APinDescription[PINS_CAN0].ulPinConfiguration); - PIO_Configure( - g_APinDescription[PINS_CAN1].pPort, - g_APinDescription[PINS_CAN1].ulPinType, - g_APinDescription[PINS_CAN1].ulPin, - g_APinDescription[PINS_CAN1].ulPinConfiguration); - - // Initialize Analog Controller - pmc_enable_periph_clk(ID_ADC); - adc_init(ADC, SystemCoreClock, ADC_FREQ_MAX, ADC_STARTUP_FAST); - adc_configure_timing(ADC, 0, ADC_SETTLING_TIME_3, 1); - adc_configure_trigger(ADC, ADC_TRIG_SW, 0); // Disable hardware trigger. - adc_disable_interrupt(ADC, 0xFFFFFFFF); // Disable all ADC interrupts. - adc_disable_all_channel(ADC); - - // Initialize analogOutput module - analogOutputInit(); -} - -#ifdef __cplusplus -} -#endif - diff --git a/Configuration.h b/Configuration.h index 306c50bc..331c3e56 100644 --- a/Configuration.h +++ b/Configuration.h @@ -24,8 +24,8 @@ Licence: GPL #define CONFIGURATION_H #define NAME "RepRapFirmware" -#define VERSION "1.00g-dc42" -#define DATE "2015-02-06" +#define VERSION "1.00h-dc42" +#define DATE "2015-02-11" #define AUTHORS "reprappro, dc42, zpl" #define FLASH_SAVE_ENABLED (1) @@ -46,6 +46,8 @@ enum Compatibility #define AUX_BAUD_RATE (57600) +const unsigned int GcodeLength = 100; // Maximum length of a G Code string that we handle + #define ABS_ZERO (-273.15) // Celsius #define INCH_TO_MM (25.4) @@ -70,6 +72,20 @@ enum Compatibility #define SILLY_Z_VALUE -9999.0 +// String lengths + +#define STRING_LENGTH 1024 +#define SHORT_STRING_LENGTH 40 + +#define FILENAME_LENGTH 100 +#define GCODE_REPLY_LENGTH 2048 + +// Print estimation defaults +#define NOZZLE_DIAMETER 0.5 // Thickness of the nozzle +#define MAX_LAYER_SAMPLES 5 // Number of layer samples (except for first layer) +#define ESTIMATION_MIN_FILAMENT_USAGE 0.025 // Minimum per cent for filament usage estimation +#define FIRST_LAYER_SPEED_FACTOR 0.25 // First layer speed compared to others (only for layer-based estimation) + // Webserver stuff #define DEFAULT_PASSWORD "reprap" @@ -71,7 +71,7 @@ void DDA::Init() } // Set up a real move. Return true if it represents real movement, else false. -bool DDA::Init(const float nextMove[], EndstopChecks ce, bool doDeltaMapping) +bool DDA::Init(const float nextMove[], EndstopChecks ce, bool doDeltaMapping, FilePosition fPos) { // 1. Compute the new endpoints and the movement vector const int32_t *positionNow = prev->DriveCoordinates(); @@ -150,6 +150,7 @@ bool DDA::Init(const float nextMove[], EndstopChecks ce, bool doDeltaMapping) // 3. Store some values endStopsToCheck = ce; + filePos = fPos; // The end coordinates will be valid at the end of this move if it does not involve endstop checks and is not a special move on a delta printer endCoordinatesValid = (ce == 0) && (doDeltaMapping || !reprap.GetMove()->IsDeltaMode()); @@ -364,7 +365,7 @@ void DDA::DoLookahead(DDA *laDDA) } } -// Recalculate the top speed, acceleration distance and deceleration distance +// Recalculate the top speed, acceleration distance and deceleration distance, and whether we can pause after this move void DDA::RecalculateMove() { accelDistance = ((requestedSpeed * requestedSpeed) - (startSpeed * startSpeed))/(2.0 * acceleration); @@ -401,6 +402,20 @@ void DDA::RecalculateMove() { topSpeed = requestedSpeed; } + + canPause = (endStopsToCheck == 0); + if (canPause && endSpeed != 0.0) + { + const Platform *p = reprap.GetPlatform(); + for (size_t drive = 0; drive < DRIVES; ++drive) + { + if (ddm[drive].moving && endSpeed * fabs(directionVector[drive]) > p->ActualInstantDv(drive)) + { + canPause = false; + break; + } + } + } } void DDA::CalcNewSpeeds() @@ -501,6 +516,7 @@ void DDA::SetPositions(const float move[DRIVES]) // Get a Cartesian end coordinate from this move float DDA::GetEndCoordinate(size_t drive, bool disableDeltaMapping) +//pre(drive < AXES) { if (disableDeltaMapping) { @@ -728,7 +744,12 @@ bool DDA::Step() break; case lowNear: - ReduceHomingSpeed(reprap.GetPlatform()->ConfiguredInstantDv(drive)); + // Only reduce homing speed if there are no more axes to be homed. + // This allows us to home X and Y simultaneously. + if (endStopsToCheck == (1 << drive)) + { + ReduceHomingSpeed(reprap.GetPlatform()->ConfiguredInstantDv(drive)); + } break; default: @@ -19,7 +19,7 @@ class DDA public: - enum DDAState + enum DDAState : unsigned char { empty, // empty or being filled in provisional, // ready, but could be subject to modifications @@ -30,7 +30,8 @@ public: DDA(DDA* n); - bool Init(const float nextMove[], EndstopChecks ce, bool doDeltaMapping); // Set up a new move, returning true if it represents real movement + bool Init(const float nextMove[], EndstopChecks ce, + bool doDeltaMapping, FilePosition fPos); // Set up a new move, returning true if it represents real movement void Init(); // Set up initial positions for machine startup bool Start(uint32_t tim); // Start executing the DDA, i.e. move the move. bool Step(); // Take one step of the DDA, called by timed interrupt. @@ -40,6 +41,7 @@ public: void Prepare(); // Calculate all the values and freeze this DDA float CalcTime() const; // Calculate the time needed for this move (used for simulation) void PrintIfHasStepError(); + bool CanPause() const { return canPause; } DDAState GetState() const { return state; } DDA* GetNext() const { return next; } @@ -52,6 +54,8 @@ public: float GetEndCoordinate(size_t drive, bool disableDeltaMapping); bool FetchEndPosition(volatile int32_t ep[DRIVES], volatile float endCoords[AXES]); void SetPositions(const float move[]); // Force the endpoints to be these + FilePosition GetFilePosition() const { return filePos; } + float GetRequestedSpeed() const { return requestedSpeed; } void DebugPrint() const; @@ -79,16 +83,21 @@ private: DDA* next; // The next one in the ring DDA *prev; // The previous one in the ring + volatile DDAState state; // what state this DDA is in + bool endCoordinatesValid; // True if endCoordinates can be relied on + bool isDeltaMovement; // True if this is a delta printer movement + bool canPause; // True if we can pause at the end of this move + + EndstopChecks endStopsToCheck; // Which endstops we are checking on this move + // We are on a half-word boundary here, so expect 2 bytes of padding to be inserted at this point + + FilePosition filePos; // The position in the SD card file after this move was read, or zero if not read fro SD card - // These remain the same regardless of how we execute a move int32_t endPoint[DRIVES]; // Machine coordinates of the endpoint float endCoordinates[AXES]; // The Cartesian coordinates at the end of the move float directionVector[DRIVES]; // The normalised direction vector - first 3 are XYZ Cartesian coordinates even on a delta - bool endCoordinatesValid; // True if endCoordinates can be relied on - bool isDeltaMovement; // True if this is a delta printer movement - EndstopChecks endStopsToCheck; // Which endstops we are checking on this move - float totalDistance; // How long is the move in hypercuboid distance + float totalDistance; // How long is the move in hypercuboid space float acceleration; // The acceleration to use float requestedSpeed; // The speed that the user asked for diff --git a/DriveMovement.cpp b/DriveMovement.cpp index b445206c..f629266a 100644 --- a/DriveMovement.cpp +++ b/DriveMovement.cpp @@ -16,9 +16,6 @@ void DriveMovement::PrepareCartesianAxis(const DDA& dda, const PrepParams& param // Acceleration phase parameters mp.cart.accelStopStep = (uint32_t)(dda.accelDistance * stepsPerMm) + 1; startSpeedTimesCdivA = params.startSpeedTimesCdivA; -#if CACHE_startSpeedTimesCdivAsquared - startSpeedTimesCdivAsquared = isquare64(startSpeedTimesCdivA); -#endif // Constant speed phase parameters mp.cart.mmPerStepTimesCdivtopSpeed = (uint32_t)(((float)DDA::stepClockRate * K1)/(stepsPerMm * dda.topSpeed)); @@ -54,9 +51,6 @@ void DriveMovement::PrepareDeltaAxis(const DDA& dda, const PrepParams& params, s // Acceleration phase parameters mp.delta.accelStopDsK = (uint32_t)(dda.accelDistance * stepsPerMm * K2); startSpeedTimesCdivA = params.startSpeedTimesCdivA; -#if CACHE_startSpeedTimesCdivAsquared - startSpeedTimesCdivAsquared = isquare64(startSpeedTimesCdivA); -#endif // Constant speed phase parameters mp.delta.mmPerStepTimesCdivtopSpeedK = (uint32_t)(((float)DDA::stepClockRate * K1)/(stepsPerMm * dda.topSpeed)); @@ -98,9 +92,6 @@ void DriveMovement::PrepareExtruder(const DDA& dda, const PrepParams& params, si // Acceleration phase parameters mp.cart.accelStopStep = (uint32_t)((dda.accelDistance * stepsPerMm) + accelCompensationSteps) + 1; startSpeedTimesCdivA = params.startSpeedTimesCdivA + compensationClocks; -#if CACHE_startSpeedTimesCdivAsquared - startSpeedTimesCdivAsquared = isquare64(startSpeedTimesCdivA); -#endif // Constant speed phase parameters mp.cart.mmPerStepTimesCdivtopSpeed = (uint32_t)(((float)DDA::stepClockRate * K1)/(stepsPerMm * dda.topSpeed)); @@ -165,14 +156,8 @@ void DriveMovement::DebugPrint(char c, bool isDeltaMovement) const if (moving || stepError) { debugPrintf("DM%c%s dir=%c steps=%u next=%u sstcda=%u " -#if CACHE_startSpeedTimesCdivAsquared - "sstcda2=%" PRIu64 " " -#endif "acmadtcdts=%d tstcdapdsc=%u tstdca2=%" PRIu64 "\n", c, (stepError) ? " ERR:" : ":", (direction) ? 'F' : 'B', totalSteps, nextStep, startSpeedTimesCdivA, -#if CACHE_startSpeedTimesCdivAsquared - startSpeedTimesCdivAsquared, -#endif accelClocksMinusAccelDistanceTimesCdivTopSpeed, topSpeedTimesCdivAPlusDecelStartClocks, twoDistanceToStopTimesCsquaredDivA); if (isDeltaMovement) @@ -215,11 +200,7 @@ uint32_t DriveMovement::CalcNextStepTimeCartesian(size_t drive) ++nextStep; if (nextStep < mp.cart.accelStopStep) { -#if CACHE_startSpeedTimesCdivAsquared - nextStepTime = isqrt(startSpeedTimesCdivAsquared + (mp.cart.twoCsquaredTimesMmPerStepDivA * nextStep)) - startSpeedTimesCdivA; -#else nextStepTime = isqrt(isquare64(startSpeedTimesCdivA) + (mp.cart.twoCsquaredTimesMmPerStepDivA * nextStep)) - startSpeedTimesCdivA; -#endif } else if (nextStep < mp.cart.decelStartStep) { @@ -293,11 +274,7 @@ uint32_t DriveMovement::CalcNextStepTimeDelta(const DDA &dda, size_t drive) } if ((uint32_t)dsK < mp.delta.accelStopDsK) { -#if CACHE_startSpeedTimesCdivAsquared - nextStepTime = isqrt(startSpeedTimesCdivAsquared + ((uint64_t)mp.delta.twoCsquaredTimesMmPerStepDivAK * (uint32_t)dsK)) - startSpeedTimesCdivA; -#else nextStepTime = isqrt(isquare64(startSpeedTimesCdivA) + ((uint64_t)mp.delta.twoCsquaredTimesMmPerStepDivAK * (uint32_t)dsK)) - startSpeedTimesCdivA; -#endif } else if ((uint32_t)dsK < mp.delta.decelStartDsK) { @@ -394,7 +371,10 @@ void DriveMovement::ReduceSpeed(const DDA& dda, float inverseSpeedFactor) } \ } - // We need to do 16 iterations + // We need to do 16 iterations. + // After the last iteration, numAll may be between 0 and (1 + 2 * res) inclusive. + // So to take square roots of numbers up to 64 bits, we need to do all these iterations using 64 bit maths. + // If we restricted the input to e.g. 48 bits, then we could do some of the final iterations using 32-bit maths. iter64b(15); iter64b(14); iter64b(13); iter64b(12); iter64b(11); iter64b(10); iter64b(9); iter64b(8); iter64b(7); iter64b(6); iter64b(5); iter64b(4); diff --git a/DriveMovement.h b/DriveMovement.h index a7c85e99..7f6fc3f4 100644 --- a/DriveMovement.h +++ b/DriveMovement.h @@ -8,9 +8,6 @@ #ifndef DRIVEMOVEMENT_H_ #define DRIVEMOVEMENT_H_ -// Set the following nonzero to cache the square of startSpeedTimesCdivA, at the cost of 64 bytes of memory per DDA -#define CACHE_startSpeedTimesCdivAsquared 0 - class DDA; // Struct for passing parameters to the DriveMovement Prepare methods @@ -48,9 +45,6 @@ public: // The following only need to be stored per-drive if we are supporting elasticity compensation uint32_t startSpeedTimesCdivA; -#if CACHE_startSpeedTimesCdivAsquared - uint64_t startSpeedTimesCdivAsquared; -#endif int32_t accelClocksMinusAccelDistanceTimesCdivTopSpeed; // this one can be negative uint32_t topSpeedTimesCdivAPlusDecelStartClocks; uint64_t twoDistanceToStopTimesCsquaredDivA; diff --git a/GCodeBuffer.cpp b/GCodeBuffer.cpp new file mode 100644 index 00000000..dd1fa296 --- /dev/null +++ b/GCodeBuffer.cpp @@ -0,0 +1,350 @@ +/* + * GCodeBuffer.cpp + * + * Created on: 6 Feb 2015 + * Author: David + */ + +//************************************************************************************* + +#include "RepRapFirmware.h" + +// This class stores a single G Code and provides functions to allow it to be parsed + +GCodeBuffer::GCodeBuffer(Platform* p, const char* id) +{ + platform = p; + identity = id; + writingFileDirectory = NULL; // Has to be done here as Init() is called every line. + toolNumberAdjust = 0; + checksumRequired = false; +} + +void GCodeBuffer::Init() +{ + gcodePointer = 0; + readPointer = -1; + inComment = false; + state = idle; +} + +int GCodeBuffer::CheckSum() const +{ + int cs = 0; + for (int i = 0; gcodeBuffer[i] != '*' && gcodeBuffer[i] != 0; i++) + { + cs = cs ^ gcodeBuffer[i]; + } + cs &= 0xff; // Defensive programming... + return cs; +} + +// Add a byte to the code being assembled. If false is returned, the code is +// not yet complete. If true, it is complete and ready to be acted upon. +bool GCodeBuffer::Put(char c) +{ + if (c == '\r') + { + // Ignore carriage return, it messes up filenames sometimes if it appears in macro files etc. + // Alternatively, we could handle it in the same way as linefeed, and add an optimisation to ignore blank lines. + return false; + } + + if (c == ';') + { + inComment = true; + } + else if (c == '\n' || !c) + { + gcodeBuffer[gcodePointer] = 0; + if (reprap.Debug(moduleGcodes) && gcodeBuffer[0] && !writingFileDirectory) // Don't bother with blank/comment lines + { + platform->Message(HOST_MESSAGE, "%s%s\n", identity, gcodeBuffer); + } + + // Deal with line numbers and checksums + if (Seen('*')) + { + int csSent = GetIValue(); + int csHere = CheckSum(); + Seen('N'); + if (csSent != csHere) + { + snprintf(gcodeBuffer, GcodeLength, "M998 P%d", GetIValue()); + Init(); + return true; + } + + // Strip out the line number and checksum + gcodePointer = 0; + while (gcodeBuffer[gcodePointer] != ' ' && gcodeBuffer[gcodePointer]) + { + gcodePointer++; + } + + // Anything there? + if (!gcodeBuffer[gcodePointer]) + { + // No... + gcodeBuffer[0] = 0; + Init(); + return false; + } + + // Yes... + gcodePointer++; + int gp2 = 0; + while (gcodeBuffer[gcodePointer] != '*' && gcodeBuffer[gcodePointer]) + { + gcodeBuffer[gp2] = gcodeBuffer[gcodePointer++]; + gp2++; + } + gcodeBuffer[gp2] = 0; + } + else if (checksumRequired) + { + gcodeBuffer[0] = 0; + Init(); + return false; + } + Init(); + return true; + } + else if (!inComment || writingFileDirectory) + { + gcodeBuffer[gcodePointer++] = c; + if (gcodePointer >= GcodeLength) + { + platform->Message(BOTH_ERROR_MESSAGE, "G-Code buffer length overflow.\n"); + gcodePointer = 0; + gcodeBuffer[0] = 0; + } + } + + return false; +} + +bool GCodeBuffer::Put(const char *str, size_t len) +{ + for(size_t i=0; i<=len; i++) + { + if (Put(str[i])) + { + return true; + } + } + + return false; +} + +// Does this buffer contain any code? + +bool GCodeBuffer::IsEmpty() const +{ + const char *buf = gcodeBuffer; + while (strchr(" \t\n\r", *buf)) + { + if (*buf == 0) + { + return true; + } + buf++; + } + return false; +} + +// Is 'c' in the G Code string? +// Leave the pointer there for a subsequent read. + +bool GCodeBuffer::Seen(char c) +{ + readPointer = 0; + for (;;) + { + char b = gcodeBuffer[readPointer]; + if (b == 0 || b == ';') break; + if (b == c) return true; + ++readPointer; + } + readPointer = -1; + return false; +} + +// Get a float after a G Code letter found by a call to Seen() + +float GCodeBuffer::GetFValue() +{ + if (readPointer < 0) + { + platform->Message(BOTH_ERROR_MESSAGE, "GCodes: Attempt to read a GCode float before a search.\n"); + readPointer = -1; + return 0.0; + } + float result = (float) strtod(&gcodeBuffer[readPointer + 1], 0); + readPointer = -1; + return result; +} + +// Get a :-separated list of floats after a key letter + +const void GCodeBuffer::GetFloatArray(float a[], int& returnedLength) +{ + int length = 0; + if(readPointer < 0) + { + platform->Message(BOTH_ERROR_MESSAGE, "GCodes: Attempt to read a GCode float array before a search.\n"); + readPointer = -1; + returnedLength = 0; + return; + } + + bool inList = true; + while(inList) + { + if(length >= returnedLength) // Array limit has been set in here + { + platform->Message(BOTH_ERROR_MESSAGE, "GCodes: Attempt to read a GCode float array that is too long: %s\n", gcodeBuffer); + readPointer = -1; + returnedLength = 0; + return; + } + a[length] = (float)strtod(&gcodeBuffer[readPointer + 1], 0); + length++; + readPointer++; + while(gcodeBuffer[readPointer] && (gcodeBuffer[readPointer] != ' ') && (gcodeBuffer[readPointer] != LIST_SEPARATOR)) + { + readPointer++; + } + if(gcodeBuffer[readPointer] != LIST_SEPARATOR) + { + inList = false; + } + } + + // Special case if there is one entry and returnedLength requests several. + // Fill the array with the first entry. + + if(length == 1 && returnedLength > 1) + { + for(int i = 1; i < returnedLength; i++) + { + a[i] = a[0]; + } + } + else + { + returnedLength = length; + } + + readPointer = -1; +} + +// Get a :-separated list of longs after a key letter + +const void GCodeBuffer::GetLongArray(long l[], int& returnedLength) +{ + if(readPointer < 0) + { + platform->Message(BOTH_ERROR_MESSAGE, "GCodes: Attempt to read a GCode long array before a search.\n"); + readPointer = -1; + return; + } + + int length = 0; + bool inList = true; + while(inList) + { + if(length >= returnedLength) // Array limit has been set in here + { + platform->Message(BOTH_ERROR_MESSAGE, "GCodes: Attempt to read a GCode long array that is too long: %s\n", gcodeBuffer); + readPointer = -1; + returnedLength = 0; + return; + } + l[length] = strtol(&gcodeBuffer[readPointer + 1], 0, 0); + length++; + readPointer++; + while(gcodeBuffer[readPointer] && (gcodeBuffer[readPointer] != ' ') && (gcodeBuffer[readPointer] != LIST_SEPARATOR)) + { + readPointer++; + } + if(gcodeBuffer[readPointer] != LIST_SEPARATOR) + { + inList = false; + } + } + returnedLength = length; + readPointer = -1; +} + +// Get a string after a G Code letter found by a call to Seen(). +// It will be the whole of the rest of the GCode string, so strings +// should always be the last parameter. + +const char* GCodeBuffer::GetString() +{ + if (readPointer < 0) + { + platform->Message(BOTH_ERROR_MESSAGE, "GCodes: Attempt to read a GCode string before a search.\n"); + readPointer = -1; + return ""; + } + const char* result = &gcodeBuffer[readPointer + 1]; + readPointer = -1; + return result; +} + +// This returns a pointer to the end of the buffer where a +// string starts. It assumes that an M or G search has +// been done followed by a GetIValue(), so readPointer will +// be -1. It absorbs "M/Gnnn " (including the space) from the +// start and returns a pointer to the next location. + +// This is provided for legacy use, in particular in the M23 +// command that sets the name of a file to be printed. In +// preference use GetString() which requires the string to have +// been preceded by a tag letter. + +const char* GCodeBuffer::GetUnprecedentedString(bool optional) +{ + readPointer = 0; + while (gcodeBuffer[readPointer] && gcodeBuffer[readPointer] != ' ') + { + readPointer++; + } + + if (!gcodeBuffer[readPointer]) + { + readPointer = -1; + if (optional) + { + return NULL; + } + platform->Message(BOTH_ERROR_MESSAGE, "GCodes: String expected but not seen.\n"); + return gcodeBuffer; // Good idea? + } + + const char* result = &gcodeBuffer[readPointer + 1]; + readPointer = -1; + return result; +} + +// Get an long after a G Code letter + +long GCodeBuffer::GetLValue() +{ + if (readPointer < 0) + { + platform->Message(BOTH_ERROR_MESSAGE, "GCodes: Attempt to read a GCode int before a search.\n"); + readPointer = -1; + return 0; + } + long result = strtol(&gcodeBuffer[readPointer + 1], 0, 0); + readPointer = -1; + return result; +} + +// End + + + diff --git a/GCodeBuffer.h b/GCodeBuffer.h new file mode 100644 index 00000000..bf7e229f --- /dev/null +++ b/GCodeBuffer.h @@ -0,0 +1,114 @@ +/* + * GCodeBuffer.h + * + * Created on: 6 Feb 2015 + * Author: David + */ + +#ifndef GCODEBUFFER_H_ +#define GCODEBUFFER_H_ + +// Small class to hold an individual GCode and provide functions to allow it to be parsed +class GCodeBuffer +{ + public: + GCodeBuffer(Platform* p, const char* id); + void Init(); // Set it up + bool Put(char c); // Add a character to the end + bool Put(const char *str, size_t len); // Add an entire string + bool IsEmpty() const; // Does this buffer contain any code? + bool Seen(char c); // Is a character present? + float GetFValue(); // Get a float after a key letter + int GetIValue(); // Get an integer after a key letter + long GetLValue(); // Get a long integer after a key letter + const char* GetUnprecedentedString(bool optional = false); // Get a string with no preceding key letter + const char* GetString(); // Get a string after a key letter + const void GetFloatArray(float a[], int& length); // Get a :-separated list of floats after a key letter + const void GetLongArray(long l[], int& length); // Get a :-separated list of longs after a key letter + const char* Buffer() const; + bool Active() const; + void SetFinished(bool f); // Set the G Code executed (or not) + void Pause(); + void CancelPause(); + void Resume(); + const char* WritingFileDirectory() const; // If we are writing the G Code to a file, where that file is + void SetWritingFileDirectory(const char* wfd); // Set the directory for the file to write the GCode in + int GetToolNumberAdjust() const { return toolNumberAdjust; } + void SetToolNumberAdjust(int arg) { toolNumberAdjust = arg; } + void SetCommsProperties(uint32_t arg) { checksumRequired = (arg & 1); } + bool StartingNewCode() const { return gcodePointer == 0; } + + private: + + enum State { idle, executing, paused }; + int CheckSum() const; // Compute the checksum (if any) at the end of the G Code + Platform* platform; // Pointer to the RepRap's controlling class + char gcodeBuffer[GcodeLength]; // The G Code + const char* identity; // Where we are from (web, file, serial line etc) + int gcodePointer; // Index in the buffer + int readPointer; // Where in the buffer to read next + bool inComment; // Are we after a ';' character? + bool checksumRequired; // True if we only accept commands with a valid checksum + State state; // Idle, executing or paused + const char* writingFileDirectory; // If the G Code is going into a file, where that is + int toolNumberAdjust; // The adjustment to tool numbers in commands we receive +}; + +// Get an Int after a G Code letter + +inline int GCodeBuffer::GetIValue() +{ + return (int)GetLValue(); +} + +inline const char* GCodeBuffer::Buffer() const +{ + return gcodeBuffer; +} + +inline bool GCodeBuffer::Active() const +{ + return state == executing; +} + +inline void GCodeBuffer::SetFinished(bool f) +{ + state = (f) ? idle : executing; +} + +inline void GCodeBuffer::Pause() +{ + if (state == executing) + { + state = paused; + } +} + +// If we paused a print, cancel printing that file and get ready to print a new one +inline void GCodeBuffer::CancelPause() +{ + if (state == paused) + { + Init(); + } +} + +inline void GCodeBuffer::Resume() +{ + if (state == paused) + { + state = executing; + } +} + +inline const char* GCodeBuffer::WritingFileDirectory() const +{ + return writingFileDirectory; +} + +inline void GCodeBuffer::SetWritingFileDirectory(const char* wfd) +{ + writingFileDirectory = wfd; +} + +#endif /* GCODEBUFFER_H_ */ @@ -27,9 +27,6 @@ const char GCodes::axisLetters[AXES] = {'X', 'Y', 'Z'}; -const float minutesToSeconds = 60.0; -const float secondsToMinutes = 1.0/minutesToSeconds; - GCodes::GCodes(Platform* p, Webserver* w) { active = false; @@ -51,21 +48,15 @@ void GCodes::Exit() void GCodes::Init() { Reset(); - drivesRelative = true; - axesRelative = false; distanceScale = 1.0; for (unsigned int extruder = 0; extruder < DRIVES - AXES; extruder++) { - lastExtruderPosition[extruder] = 0.0; + lastRawExtruderPosition[extruder] = 0.0; } configFile = NULL; eofString = EOF_STRING; eofStringCounter = 0; eofStringLength = strlen(eofString); - homing = false; - homeX = false; - homeY = false; - homeZ = false; offSetSet = false; zProbesSet = false; active = true; @@ -73,8 +64,6 @@ void GCodes::Init() dwellTime = longWait; limitAxes = true; SetAllAxesNotHomed(); - toolChangeSequence = 0; - setBedState = 0; coolingInverted = false; } @@ -95,40 +84,64 @@ void GCodes::Reset() fractionOfFilePrinted = -1.0; dwellWaiting = false; stackPointer = 0; - waitingForMoveToComplete = false; + state = GCodeState::normal; + drivesRelative = true; + axesRelative = false; probeCount = 0; cannedCycleMoveCount = 0; cannedCycleMoveQueued = false; - speedFactor = 1.0/60.0; // default is just to convert from mm/minute to mm/second + speedFactor = 1.0/minutesToSeconds; // default is just to convert from mm/minute to mm/second speedFactorChange = 1.0; for (size_t i = 0; i < DRIVES - AXES; ++i) { extrusionFactors[i] = 1.0; } + auxDetected = false; simulating = false; simulationTime = 0.0; + isPaused = false; + filePos = moveFilePos = noFilePosition; } -void GCodes::DoFilePrint(GCodeBuffer* gb) +void GCodes::DoFilePrint(GCodeBuffer* gb, StringRef& reply) { - char b; - - if (fileBeingPrinted.IsLive()) + for (int i = 0; i < 50 && fileBeingPrinted.IsLive(); ++i) { + char b; if (fileBeingPrinted.Read(b)) { + if (gb->StartingNewCode() && gb == fileGCode) + { + filePos = fileBeingPrinted.GetPosition() - 1; + //debugPrintf("Set file pos %u\n", filePos); + } if (gb->Put(b)) { - gb->SetFinished(ActOnCode(gb)); + gb->SetFinished(ActOnCode(gb, reply)); + break; } } else { - if (gb->Put('\n')) // In case there wasn't one ending the file + // We have reached the end of the file. + // Don't close the file until all moves have been completed, in case the print gets paused. + // Also, this keeps the state as 'Printing' until the print really has finished. + if (!gb->StartingNewCode()) // if there is something in the buffer + { + if (gb->Put('\n')) // in case there wasn't one ending the file + { + gb->SetFinished(ActOnCode(gb, reply)); + } + else + { + gb->Init(); + } + } + else if (AllMovesAreFinishedAndMoveBufferIsLoaded()) { - gb->SetFinished(ActOnCode(gb)); + fileBeingPrinted.Close(); } - fileBeingPrinted.Close(); + break; } } } @@ -138,6 +151,198 @@ void GCodes::Spin() if (!active) return; + char replyBuffer[STRING_LENGTH]; + StringRef reply(replyBuffer, ARRAY_SIZE(replyBuffer)); + reply.Clear(); + + // Perform the next operation of the state machine + // Note: if we change the state to 'normal' from another state, we must call HandleReply to tell the host about the command we have just completed. + switch (state) + { + case GCodeState::normal: + StartNextGCode(reply); + break; + + case GCodeState::waitingForMoveToComplete: + if (AllMovesAreFinishedAndMoveBufferIsLoaded()) + { + HandleReply(false, gbCurrent, reply.Pointer(), 'G', 1, false); + state = GCodeState::normal; + } + break; + + case GCodeState::homing: + if (toBeHomed & (1 << X_AXIS)) + { + toBeHomed &= ~(1 << X_AXIS); + DoFileMacro(HOME_X_G); + } + else if (toBeHomed & (1 << Y_AXIS)) + { + toBeHomed &= ~(1 << Y_AXIS); + DoFileMacro(HOME_Y_G); + } + else if (toBeHomed & (1 << Z_AXIS)) + { + toBeHomed &= ~(1 << Z_AXIS); + DoFileMacro(HOME_Z_G); + } + else + { + HandleReply(false, gbCurrent, reply.Pointer(), 'G', 28, false); + state = GCodeState::normal; + } + break; + + case GCodeState::setBed1: + if (reprap.GetMove()->NumberOfXYProbePoints() < 3) + { + reply.copy("Bed probing: there needs to be 3 or more points set.\n"); + HandleReply(false, gbCurrent, reply.Pointer(), 'G', 32, false); + state = GCodeState::normal; + } + else + { + // zpl 2014-11-02: When calling G32, ensure bed compensation parameters are initially reset + reprap.GetMove()->SetIdentityTransform(); + probeCount = 0; + state = GCodeState::setBed2; + } + break; + + case GCodeState::setBed2: + { + int numProbePoints = reprap.GetMove()->NumberOfXYProbePoints(); + if (DoSingleZProbeAtPoint(probeCount)) + { + probeCount++; + if (probeCount >= numProbePoints) + { + probeCount = 0; + zProbesSet = true; + reprap.GetMove()->FinishedBedProbing(0, numProbePoints, reply); + HandleReply(false, gbCurrent, reply.Pointer(), 'G', 32, false); + state = GCodeState::normal; + } + } + } + break; + + case GCodeState::toolChange1: // Release the old tool (if any) + { + const Tool *oldTool = reprap.GetCurrentTool(); + if (oldTool != NULL) + { + reprap.StandbyTool(oldTool->Number()); + } + } + state = GCodeState::toolChange2; + if (reprap.GetTool(newToolNumber) != NULL) + { + scratchString.printf("tpre%d.g", newToolNumber); + DoFileMacro(scratchString.Pointer()); + } + break; + + case GCodeState::toolChange2: // Select the new tool (even if it doesn't exist - that just deselects all tools) + reprap.SelectTool(newToolNumber); + state = GCodeState::toolChange3; + if (reprap.GetTool(newToolNumber) != NULL) + { + scratchString.printf("tpost%d.g", newToolNumber); + DoFileMacro(scratchString.Pointer()); + } + break; + + case GCodeState::toolChange3: + HandleReply(false, gbCurrent, reply.Pointer(), 'T', newToolNumber, false); + state = GCodeState::normal; + break; + + case GCodeState::pausing1: + if (AllMovesAreFinishedAndMoveBufferIsLoaded()) + { + state = GCodeState::pausing2; + DoFileMacro(PAUSE_G); + } + break; + + case GCodeState::pausing2: + HandleReply(false, gbCurrent, reply.Pointer(), 'M', 25, false); + state = GCodeState::normal; + break; + + case GCodeState::resuming1: + case GCodeState::resuming2: + // Here when we have just finished running the resume macro file. + // Move the head back to the paused location + if (AllMovesAreFinishedAndMoveBufferIsLoaded()) + { + float currentZ = moveBuffer[Z_AXIS]; + memcpy(moveBuffer, pausedMoveBuffer, sizeof(moveBuffer)); + moveBuffer[DRIVES] = 5000/minutesToSeconds; // ask for a good feed rate, we may have paused during a slow move + disableDeltaMapping = false; + endStopsToCheck = 0; + moveFilePos = noFilePosition; + if (state == GCodeState::resuming1 && currentZ > pausedMoveBuffer[Z_AXIS]) + { + // First move the head to the correct XY point, then move it down in a separate move + moveBuffer[Z_AXIS] = currentZ; + state = GCodeState::resuming2; + } + else + { + // Just move to the saved position in one go + state = GCodeState::resuming3; + } + moveAvailable = true; + } + break; + + case GCodeState::resuming3: + if (AllMovesAreFinishedAndMoveBufferIsLoaded()) + { + platform->SetFanValue(pausedFanValue); + fileBeingPrinted.MoveFrom(fileToPrint); + moveBuffer[DRIVES] = pausedMoveBuffer[DRIVES]; + reprap.GetMove()->SetFeedrate(pausedMoveBuffer[DRIVES]); + fractionOfFilePrinted = -1.0; + fileGCode->Resume(); + HandleReply(false, gbCurrent, reply.Pointer(), 'M', 24, false); + isPaused = false; + state = GCodeState::normal; + } + break; + + default: // should not happen + //TODO report an error + break; + } +} + +void GCodes::StartNextGCode(StringRef& reply) +{ + // If a file macro is running, we don't allow anything to interrupt it + // TODO process M105 requests from Pronterface and PanelDue during file macro execution + if (doingFileMacro) + { + // Complete the current move (must do this before checking whether we have finished the file in case it didn't end in newline) + if (fileMacroGCode->Active()) + { + fileMacroGCode->SetFinished(ActOnCode(fileMacroGCode, reply)); + } + else if (fileBeingPrinted.IsLive()) // Have we finished the file? + { + DoFilePrint(fileMacroGCode, reply); // No - Do more of the file + } + else if (AllMovesAreFinishedAndMoveBufferIsLoaded()) + { + Pop(); + fileMacroGCode->Init(); + } + return; + } + // Check each of the sources of G Codes (web, serial, queued and file) to // see if they are finished in order to feed them new codes. // @@ -160,13 +365,13 @@ void GCodes::Spin() } else { - webGCode->SetFinished(ActOnCode(webGCode)); + webGCode->SetFinished(ActOnCode(webGCode, reply)); } break; // stop after receiving a complete gcode in case we haven't finished processing it } ++i; } while (i < 16 && webserver->GCodeAvailable()); - platform->ClassReport("GCodes", longWait, moduleGcodes); + platform->ClassReport(longWait); return; } @@ -180,7 +385,7 @@ void GCodes::Spin() char b; platform->GetLine()->Read(b); WriteHTMLToFile(b, serialGCode); - platform->ClassReport("GCodes", longWait, moduleGcodes); + platform->ClassReport(longWait); return; } @@ -202,13 +407,13 @@ void GCodes::Spin() } else { - serialGCode->SetFinished(ActOnCode(serialGCode)); + serialGCode->SetFinished(ActOnCode(serialGCode, reply)); } break; // stop after receiving a complete gcode in case we haven't finished processing it } ++i; } while (i < 16 && (platform->GetLine()->Status() & byteAvailable)); - platform->ClassReport("GCodes", longWait, moduleGcodes); + platform->ClassReport(longWait); return; } } @@ -224,7 +429,8 @@ void GCodes::Spin() platform->GetAux()->Read(b); if (auxGCode->Put(b)) // add char to buffer and test whether the gcode is complete { - auxGCode->SetFinished(ActOnCode(auxGCode)); + auxDetected = true; + auxGCode->SetFinished(ActOnCode(auxGCode, reply)); break; // stop after receiving a complete gcode in case we haven't finished processing it } ++i; @@ -233,28 +439,28 @@ void GCodes::Spin() else if (webGCode->Active()) { // Note: Direct web-printing has been dropped, so it's safe to execute web codes immediately - webGCode->SetFinished(ActOnCode(webGCode)); + webGCode->SetFinished(ActOnCode(webGCode, reply)); } else if (serialGCode->Active()) { // We want codes from the serial interface to be queued unless the print has been paused - serialGCode->SetFinished(ActOnCode(serialGCode)); + serialGCode->SetFinished(ActOnCode(serialGCode, reply)); } else if (auxGCode->Active()) { // Same goes for our auxiliary interface - auxGCode->SetFinished(ActOnCode(auxGCode)); + auxGCode->SetFinished(ActOnCode(auxGCode, reply)); } else if (fileGCode->Active()) { - fileGCode->SetFinished(ActOnCode(fileGCode)); + fileGCode->SetFinished(ActOnCode(fileGCode, reply)); } else { - DoFilePrint(fileGCode); // else see if there is anything to print from file + DoFilePrint(fileGCode, reply); // else see if there is anything to print from file } - platform->ClassReport("GCodes", longWait, moduleGcodes); + platform->ClassReport(longWait); } void GCodes::Diagnostics() @@ -279,66 +485,57 @@ bool GCodes::AllMovesAreFinishedAndMoveBufferIsLoaded() return false; reprap.GetMove()->ResumeMoving(); - // Load the last position; If Move can't accept more, return false - should never happen reprap.GetMove()->GetCurrentUserPosition(moveBuffer, false); return true; } // Save (some of) the state of the machine for recovery in the future. -// Call repeatedly till it returns true. - -bool GCodes::Push() +void GCodes::Push() { - if (stackPointer >= STACK) + if (stackPointer >= StackSize) { platform->Message(BOTH_ERROR_MESSAGE, "Push(): stack overflow!\n"); - return true; + return; } - if (!AllMovesAreFinishedAndMoveBufferIsLoaded()) - return false; - + stack[stackPointer].state = state; + stack[stackPointer].gb = gbCurrent; + stack[stackPointer].feedrate = moveBuffer[DRIVES]; + stack[stackPointer].fileState.CopyFrom(fileBeingPrinted); stack[stackPointer].drivesRelative = drivesRelative; stack[stackPointer].axesRelative = axesRelative; stack[stackPointer].doingFileMacro = doingFileMacro; - stack[stackPointer].feedrate = moveBuffer[DRIVES]; - stack[stackPointer].fileState.CopyFrom(fileBeingPrinted); if (stackPointer == 0) { fractionOfFilePrinted = fileBeingPrinted.FractionRead(); // save this so that we don't return the fraction of the macro file read } stackPointer++; platform->PushMessageIndent(); - return true; } -// Recover a saved state. Call repeatedly till it returns true. - -bool GCodes::Pop() +// Recover a saved state +void GCodes::Pop() { if (stackPointer < 1) { platform->Message(BOTH_ERROR_MESSAGE, "Pop(): stack underflow!\n"); - return true; + return; } - if(!AllMovesAreFinishedAndMoveBufferIsLoaded()) - return false; - stackPointer--; if (stackPointer == 0) { fractionOfFilePrinted = -1.0; // restore live updates of fraction read from the file being printed } + state = stack[stackPointer].state; + gbCurrent = stack[stackPointer].gb; + moveBuffer[DRIVES] = stack[stackPointer].feedrate; + fileBeingPrinted.MoveFrom(stack[stackPointer].fileState); drivesRelative = stack[stackPointer].drivesRelative; axesRelative = stack[stackPointer].axesRelative; doingFileMacro = stack[stackPointer].doingFileMacro; - moveBuffer[DRIVES] = stack[stackPointer].feedrate; - fileBeingPrinted.MoveFrom(stack[stackPointer].fileState); - endStopsToCheck = 0; platform->PopMessageIndent(); - return true; } // Move expects all axis movements to be absolute, and all @@ -400,17 +597,17 @@ bool GCodes::LoadMoveBufferFromGCode(GCodeBuffer *gb, bool doingG92, bool applyL if(doingG92) { moveBuffer[drive + AXES] = 0.0; // no move required - lastExtruderPosition[drive] = moveArg; + lastRawExtruderPosition[drive] = moveArg; } else if(drivesRelative) { moveBuffer[drive + AXES] = moveArg * extrusionFactors[drive]; - lastExtruderPosition[drive] += moveArg; + lastRawExtruderPosition[drive] += moveArg; } else { - moveBuffer[drive + AXES] = (moveArg - lastExtruderPosition[drive]) * extrusionFactors[drive]; - lastExtruderPosition[drive] = moveArg; + moveBuffer[drive + AXES] = (moveArg - lastRawExtruderPosition[drive]) * extrusionFactors[drive]; + lastRawExtruderPosition[drive] = moveArg; } } } @@ -541,99 +738,66 @@ int GCodes::SetUpMove(GCodeBuffer *gb, StringRef& reply) // Load the move buffer with either the absolute movement required or the relative movement required moveAvailable = LoadMoveBufferFromGCode(gb, false, limitAxes && !disableDeltaMapping); + if (moveAvailable) + { + moveFilePos = (gb == fileGCode) ? filePos : noFilePosition; + //debugPrintf("Queue move pos %u\n", moveFilePos); + } return (disableDeltaMapping) ? 2 : 1; // note that disableDeltaMapping is true if there are any endstops to check, even on a Cartesian printer } // The Move class calls this function to find what to do next. -bool GCodes::ReadMove(float m[], EndstopChecks& ce, bool& noDeltaMapping) +bool GCodes::ReadMove(float m[], EndstopChecks& ce, bool& noDeltaMapping, FilePosition& fPos) { if (!moveAvailable) { return false; } - for (int8_t i = 0; i <= DRIVES; i++) // 1 more for feedrate + for (size_t i = 0; i <= DRIVES; i++) // 1 more for feedrate { m[i] = moveBuffer[i]; } ce = endStopsToCheck; noDeltaMapping = disableDeltaMapping; + fPos = moveFilePos; + ClearMove(); + return true; +} +void GCodes::ClearMove() +{ moveAvailable = false; endStopsToCheck = 0; disableDeltaMapping = false; - return true; } -// Run the specified macro file. -bool GCodes::DoFileMacro(const char* fileName) +// Run a file macro. Prior to calling this, 'state' must be set to the state we want to enter when the macro has been completed. +void GCodes::DoFileMacro(const char* fileName) { - // Have we started the file? - if (!doingFileMacro) + FileStore *f = platform->GetFileStore((fileName[0] == '/') ? "0:" : platform->GetSysDir(), fileName, false); + if (f == NULL) { - // No - if (!Push()) - { - return false; - } - - FileStore *f = platform->GetFileStore(platform->GetSysDir(), fileName, false); - if (f == NULL) - { - // Don't use snprintf into scratchString here, because fileName may be aliased to scratchString - platform->Message(BOTH_ERROR_MESSAGE, "Macro file %s not found.\n", fileName); - if (!Pop()) - { - platform->Message(BOTH_ERROR_MESSAGE, "Cannot pop the stack.\n"); - } - return true; - } - fileBeingPrinted.Set(f); - doingFileMacro = true; - fileMacroGCode->Init(); - return false; + // Don't use snprintf into scratchString here, because fileName may be aliased to scratchString + platform->Message(BOTH_ERROR_MESSAGE, "Macro file %s not found.\n", fileName); + return; } - // Complete the current move (must do this before checking whether we have finished the file in case it didn't end in newline) - if (fileMacroGCode->Active()) - { - fileMacroGCode->SetFinished(ActOnCode(fileMacroGCode)); - return false; - } + Push(); + fileBeingPrinted.Set(f); + doingFileMacro = true; + fileMacroGCode->Init(); + state = GCodeState::normal; +} - // Have we finished the file? - if (!fileBeingPrinted.IsLive()) +void GCodes::FileMacroCyclesReturn() +{ + if (doingFileMacro) { - // Yes - if (!Pop()) - { - return false; - } - - doingFileMacro = false; + Pop(); fileMacroGCode->Init(); - return true; } - - // No - Do more of the file - DoFilePrint(fileMacroGCode); - return false; -} - -bool GCodes::FileMacroCyclesReturn() -{ - if (!doingFileMacro) - return true; - - if (!AllMovesAreFinishedAndMoveBufferIsLoaded()) - return false; - - doingFileMacro = false; - fileMacroGCode->Init(); - - fileBeingPrinted.Close(); - return true; } // To execute any move, call this until it returns true. @@ -642,23 +806,21 @@ bool GCodes::FileMacroCyclesReturn() // you want (if action[DRIVES] is true). bool GCodes::DoCannedCycleMove(EndstopChecks ce) { + if (!AllMovesAreFinishedAndMoveBufferIsLoaded()) + { + return false; + } + // Is the move already running? if (cannedCycleMoveQueued) { // Yes. - if (!Pop()) // Wait for the move to finish then restore the state - { - return false; - } + Pop(); cannedCycleMoveQueued = false; return true; } else { // No. - if (!Push()) // Wait for the RepRap to finish whatever it was doing, save it's state, and load moveBuffer[] with the current position. - { - return false; - } - + Push(); for (size_t drive = 0; drive <= DRIVES; drive++) { if (activeDrive[drive]) @@ -699,7 +861,7 @@ bool GCodes::OffsetAxes(GCodeBuffer* gb) { if (!AllMovesAreFinishedAndMoveBufferIsLoaded()) return false; - for (int8_t drive = 0; drive <= DRIVES; drive++) + for (size_t drive = 0; drive <= DRIVES; drive++) { if (drive < AXES || drive == DRIVES) { @@ -714,7 +876,7 @@ bool GCodes::OffsetAxes(GCodeBuffer* gb) activeDrive[drive] = false; } - for (int8_t axis = 0; axis < AXES; axis++) + for (size_t axis = 0; axis < AXES; axis++) { if (gb->Seen(axisLetters[axis])) { @@ -748,114 +910,6 @@ bool GCodes::OffsetAxes(GCodeBuffer* gb) return false; } -// Home one or more of the axes. Which ones are decided by the -// booleans homeX, homeY and homeZ. -// Returns true if completed, false if needs to be called again. -// 'reply' is only written if there is an error. -// 'error' is false on entry, gets changed to true if there is an error. -bool GCodes::HomeCartesian(StringRef& reply, bool& error) -//pre(reply.upb == STRING_LENGTH) -{ - if (homeX && homeY && homeZ) - { - if (!homing) - { - homing = true; - SetAllAxesNotHomed(); - } - if (DoFileMacro(HOME_ALL_G)) - { - homing = false; - homeX = false; - homeY = false; - homeZ = false; - return true; - } - return false; - } - - if (homeX) - { - if (!homing) - { - homing = true; - axisIsHomed[X_AXIS] = false; - } - if (DoFileMacro(HOME_X_G)) - { - homing = false; - homeX = false; - return NoHome(); - } - return false; - } - - if (homeY) - { - if (!homing) - { - homing = true; - axisIsHomed[Y_AXIS] = false; - } - if (DoFileMacro(HOME_Y_G)) - { - homing = false; - homeY = false; - return NoHome(); - } - return false; - } - - if (homeZ) - { - if (platform->MustHomeXYBeforeZ() && (!axisIsHomed[X_AXIS] || !axisIsHomed[Y_AXIS])) - { - // We can only home Z if X and Y have already been homed - reply.copy("Must home X and Y before homing Z"); - error = true; - homing = false; - homeZ = false; - return true; - } - if (!homing) - { - homing = true; - axisIsHomed[Z_AXIS] = false; - } - if (DoFileMacro(HOME_Z_G)) - { - homing = false; - homeZ = false; - return NoHome(); - } - return false; - } - - // Should never get here - endStopsToCheck = 0; - moveAvailable = false; - - return true; -} - -bool GCodes::HomeDelta(StringRef& reply, bool& error) -{ - if (!homing) - { - homing = true; - SetAllAxesNotHomed(); - } - if (DoFileMacro(HOME_DELTA_G)) - { - homing = false; - homeX = false; - homeY = false; - homeZ = false; - return true; - } - return false; -} - // This lifts Z a bit, moves to the probe XY coordinates (obtained by a call to GetProbeCoordinates() ), // probes the bed height, and records the Z coordinate probed. If you want to program any general // internal canned cycle, this shows how to do it. @@ -1031,66 +1085,19 @@ bool GCodes::SetSingleZProbeAtAPosition(GCodeBuffer *gb, StringRef& reply) // This probes multiple points on the bed (three in a triangle or four in the corners), // then sets the bed transformation to compensate for the bed not quite being the plane Z = 0. // Called to execute a G32 command. -bool GCodes::SetBedEquationWithProbe(int sParam, StringRef& reply) +void GCodes::SetBedEquationWithProbe(int sParam, StringRef& reply) { // zpl-2014-10-09: In order to stay compatible with old firmware versions, only execute bed.g // if it is actually present in the sys directory - switch (setBedState) + FileStore *f = platform->GetFileStore(SYS_DIR, SET_BED_EQUATION, false); + if (f != NULL) { - case 0: - { - FileStore *f = platform->GetFileStore(SYS_DIR, SET_BED_EQUATION, false); - if (f != NULL) - { - f->Close(); - setBedState = 1; - } - else - { - setBedState = 2; - } - } - return false; - - case 1: - { - bool finished = DoFileMacro(SET_BED_EQUATION); - if (finished) - { - setBedState = 0; - } - return finished; - } - - case 2: - if (reprap.GetMove()->NumberOfXYProbePoints() < 3) - { - reply.copy("Bed probing: there needs to be 3 or more points set.\n"); - setBedState = 0; - return true; - } - - // zpl 2014-11-02: When calling G32, ensure bed compensation parameters are initially reset - reprap.GetMove()->SetIdentityTransform(); - ++setBedState; - return false; - - case 3: - if (DoSingleZProbeAtPoint(probeCount)) - { - probeCount++; - } - - int numProbePoints = reprap.GetMove()->NumberOfXYProbePoints(); - if (probeCount >= numProbePoints) - { - probeCount = 0; - zProbesSet = true; - reprap.GetMove()->FinishedBedProbing(0, numProbePoints, reply); - setBedState = 0; - return true; - } - return false; + f->Close(); + DoFileMacro(SET_BED_EQUATION); + } + else + { + state = GCodeState::setBed1; } } @@ -1303,7 +1310,7 @@ void GCodes::QueueFileToPrint(const char* fileName) // Reset all extruder positions when starting a new print for (int8_t extruder = AXES; extruder < DRIVES; extruder++) { - lastExtruderPosition[extruder - AXES] = 0.0; + lastRawExtruderPosition[extruder - AXES] = 0.0; } fileToPrint.Set(f); @@ -1539,9 +1546,7 @@ void GCodes::AddNewTool(GCodeBuffer *gb, StringRef& reply) void GCodes::DisableDrives() { - if (!AllMovesAreFinishedAndMoveBufferIsLoaded()) - return; - for (int8_t drive = 0; drive < DRIVES; drive++) + for (size_t drive = 0; drive < DRIVES; drive++) { platform->Disable(drive); } @@ -1639,13 +1644,15 @@ void GCodes::SetMACAddress(GCodeBuffer *gb) } } +// Handle sending a reply back to the appropriate interface(s). +// Note that 'reply' may be null. void GCodes::HandleReply(bool error, const GCodeBuffer *gb, const char* reply, char gMOrT, int code, bool resend) { // UART device, may be used for auxiliary purposes e.g. LCD control panel if (gb == auxGCode) { // Command was received from the aux interface (LCD display), so send the response only to the aux interface. - if (reply[0] != 0) + if (reply != nullptr && reply[0] != 0) { platform->GetAux()->Write(reply); } @@ -1656,8 +1663,10 @@ void GCodes::HandleReply(bool error, const GCodeBuffer *gb, const char* reply, c // The browser only fetches replies once a second or so. Therefore, when we send a web command in the middle of an SD card print, // in order to be sure that we see the reply in the web interface, we must not send empty responses to the web interface unless // the corresponding command also came from the web interface. - if ( reply[0] != 0 // don't send empty replies to the web server, they overwrite more useful replies + if ( reply != nullptr + && reply[0] != 0 // don't send empty replies to the web server, they overwrite more useful replies && (gMOrT != 'M' || (code != 111 && code != 122)) // web server reply for M111 and M122 is handled before we get here + && (gMOrT != 'M' || (code != 105 && code != 20) || gb == webGCode) // don't echo M105 requests and file lists from Pronterface etc. to the web server ) { platform->Message((error) ? WEB_ERROR_MESSAGE : WEB_MESSAGE, reply); @@ -1675,14 +1684,20 @@ void GCodes::HandleReply(bool error, const GCodeBuffer *gb, const char* reply, c { platform->GetLine()->Write("Error: "); } - platform->GetLine()->Write(reply); + if (reply) + { + platform->GetLine()->Write(reply); + } return; case marlin: if (gMOrT == 'M' && code == 20) { platform->GetLine()->Write("Begin file list\n"); - platform->GetLine()->Write(reply); + if (reply) + { + platform->GetLine()->Write(reply); + } platform->GetLine()->Write("End file list\n"); platform->GetLine()->Write(response); platform->GetLine()->Write('\n'); @@ -1693,19 +1708,25 @@ void GCodes::HandleReply(bool error, const GCodeBuffer *gb, const char* reply, c { platform->GetLine()->Write(response); platform->GetLine()->Write('\n'); - platform->GetLine()->Write(reply); + if (reply) + { + platform->GetLine()->Write(reply); + } return; } if ((gMOrT == 'M' && code == 105) || (gMOrT == 'G' && code == 998)) { platform->GetLine()->Write(response); - platform->GetLine()->Write(' '); - platform->GetLine()->Write(reply); + if (reply) + { + platform->GetLine()->Write(' '); + platform->GetLine()->Write(reply); + } return; } - if (reply[0]) + if (reply && reply[0]) { platform->GetLine()->Write(reply); } @@ -1897,7 +1918,7 @@ void GCodes::SetToolHeaters(Tool *tool, float temperature) // otherwise false. It is called repeatedly for a given // code until it returns true for that code. -bool GCodes::ActOnCode(GCodeBuffer *gb) +bool GCodes::ActOnCode(GCodeBuffer *gb, StringRef& reply) { // Discard empty buffers right away if (gb->IsEmpty()) @@ -1905,37 +1926,36 @@ bool GCodes::ActOnCode(GCodeBuffer *gb) return true; } + gbCurrent = gb; + // M-code parameters might contain letters T and G, e.g. in filenames. // dc42 assumes that G-and T-code parameters never contain the letter M. // Therefore we must check for an M-code first. if (gb->Seen('M')) { - return HandleMcode(gb); + return HandleMcode(gb, reply); } // dc42 doesn't think a G-code parameter ever contains letter T, or a T-code ever contains letter G. // So it doesn't matter in which order we look for them. if (gb->Seen('G')) { - return HandleGcode(gb); + return HandleGcode(gb, reply); } if (gb->Seen('T')) { - return HandleTcode(gb); + return HandleTcode(gb, reply); } // An invalid or queued buffer gets discarded - HandleReply(false, gb, "", 'X', 0, false); + HandleReply(false, gb, nullptr, 'X', 0, false); return true; } -bool GCodes::HandleGcode(GCodeBuffer* gb) +bool GCodes::HandleGcode(GCodeBuffer* gb, StringRef& reply) { bool result = true; bool error = false; bool resend = false; - char replyBuffer[STRING_LENGTH]; - StringRef reply(replyBuffer, ARRAY_SIZE(replyBuffer)); - reply.Clear(); int code = gb->GetIValue(); if (simulating && code != 0 && code != 1 && code != 4 && code != 10 && code != 20 && code != 21 && code != 90 && code != 91 && code != 92) @@ -1947,25 +1967,13 @@ bool GCodes::HandleGcode(GCodeBuffer* gb) { case 0: // There are no rapid moves... case 1: // Ordinary move - if (waitingForMoveToComplete) - { - // We have already set up this move, but it does endstop checks, so wait for it to complete. - // Otherwise, if the next move uses relative coordinates, it will be incorrectly calculated. - // Or we're just performing an isolated move while the Move class is paused. - result = AllMovesAreFinishedAndMoveBufferIsLoaded(); - if (result) - { - waitingForMoveToComplete = false; - } - } - else { int res = SetUpMove(gb, reply); if (res == 2) { - waitingForMoveToComplete = true; + state = GCodeState::waitingForMoveToComplete; } - result = (res == 1); + result = (res != 0); } break; @@ -1973,7 +1981,7 @@ bool GCodes::HandleGcode(GCodeBuffer* gb) result = DoDwell(gb); break; - case 10: // Set/report offsets + case 10: // Set/report offsets and temperatures SetOrReportOffsets(reply, gb); break; @@ -1986,37 +1994,62 @@ bool GCodes::HandleGcode(GCodeBuffer* gb) break; case 28: // Home + if (!AllMovesAreFinishedAndMoveBufferIsLoaded()) + { + return false; + } + if (reprap.GetMove()->IsDeltaMode()) { - result = HomeDelta(reply, error); + SetAllAxesNotHomed(); + DoFileMacro(HOME_DELTA_G); } else { - if (NoHome()) + toBeHomed = 0; + for (size_t axis = 0; axis < AXES; ++axis) { - homeX = gb->Seen(axisLetters[X_AXIS]); - homeY = gb->Seen(axisLetters[Y_AXIS]); - homeZ = gb->Seen(axisLetters[Z_AXIS]); - if (NoHome()) + if (gb->Seen(axisLetters[axis])) { - homeX = true; - homeY = true; - homeZ = true; + toBeHomed |= (1 << axis); + axisIsHomed[axis] = false; } } - result = HomeCartesian(reply, error); + + if (toBeHomed == 0 || toBeHomed == ((1 << X_AXIS) | (1 << Y_AXIS) | (1 << Z_AXIS))) + { + SetAllAxesNotHomed(); + DoFileMacro(HOME_ALL_G); + } + else + { + state = GCodeState::homing; + } } break; case 30: // Z probe/manually set at a position and set that as point P + if (!AllMovesAreFinishedAndMoveBufferIsLoaded()) + { + return false; + } result = SetSingleZProbeAtAPosition(gb, reply); break; case 31: // Return the probe value, or set probe variables + if (!AllMovesAreFinishedAndMoveBufferIsLoaded()) + { + return false; + } result = SetPrintZProbe(gb, reply); break; case 32: // Probe Z at multiple positions and generate the bed transform + if (!AllMovesAreFinishedAndMoveBufferIsLoaded()) + { + return false; + } + if (!(axisIsHomed[X_AXIS] && axisIsHomed[Y_AXIS])) { // We can only do bed levelling if X and Y have already been homed @@ -2026,7 +2059,7 @@ bool GCodes::HandleGcode(GCodeBuffer* gb) else { int sParam = (gb->Seen('S')) ? gb->GetIValue() : 0; - result = SetBedEquationWithProbe(sParam, reply); + SetBedEquationWithProbe(sParam, reply); } break; @@ -2050,21 +2083,18 @@ bool GCodes::HandleGcode(GCodeBuffer* gb) error = true; reply.printf("invalid G Code: %s\n", gb->Buffer()); } - if (result) + if (result && state == GCodeState::normal) { HandleReply(error, gb, reply.Pointer(), 'G', code, resend); } return result; } -bool GCodes::HandleMcode(GCodeBuffer* gb) +bool GCodes::HandleMcode(GCodeBuffer* gb, StringRef& reply) { bool result = true; bool error = false; bool resend = false; - char replyBuffer[STRING_LENGTH]; - StringRef reply(replyBuffer, ARRAY_SIZE(replyBuffer)); - reply.Clear(); int code = gb->GetIValue(); if (simulating && (code < 20 || code > 37) && code != 82 && code != 83 && code != 999 && code != 111 && code != 122) @@ -2081,13 +2111,13 @@ bool GCodes::HandleMcode(GCodeBuffer* gb) if (fileBeingPrinted.IsLive()) { - fileToPrint.MoveFrom(fileBeingPrinted); + fileBeingPrinted.Close(); } // Deselect the active tool { Tool* tool = reprap.GetCurrentTool(); - if(tool != NULL) + if (tool != NULL) { reprap.StandbyTool(tool->Number()); } @@ -2101,6 +2131,7 @@ bool GCodes::HandleMcode(GCodeBuffer* gb) } reprap.GetHeat()->SwitchOffAll(); + isPaused = false; break; case 18: // Motors off @@ -2201,6 +2232,12 @@ bool GCodes::HandleMcode(GCodeBuffer* gb) case 23: // Set file to print case 32: // Select file and start SD print + if (isPaused) + { + reply.copy("Cannot set file to print, because another print is still paused. Run M0 first."); + break; + } + else { const char* filename = gb->GetUnprecedentedString(); reprap.StartingFilePrint(filename); @@ -2218,20 +2255,72 @@ bool GCodes::HandleMcode(GCodeBuffer* gb) // no break otherwise case 24: // Print/resume-printing the selected file + if (!AllMovesAreFinishedAndMoveBufferIsLoaded()) + { + return false; + } + if (!fileToPrint.IsLive()) { reply.copy("Cannot resume print, because no print is in progress!\n"); error = true; - break; } - - fileBeingPrinted.MoveFrom(fileToPrint); - fractionOfFilePrinted = -1.0; - fileGCode->Resume(); + else if (isPaused) + { + fileGCode->Resume(); + state = GCodeState::resuming1; + DoFileMacro(RESUME_G); + } + else + { + fileBeingPrinted.MoveFrom(fileToPrint); + fractionOfFilePrinted = -1.0; + } break; + case 226: // Gcode Initiated Pause + if (!AllMovesAreFinishedAndMoveBufferIsLoaded()) + return false; + // no break + case 25: // Pause the print - fileToPrint.MoveFrom(fileBeingPrinted); + if (!PrintingAFile()) + { + reply.copy("Cannot pause print, because no file is being printed!\n"); + error = true; + } + else if (doingFileMacro) + { + reply.copy("Cannot pause macro files, wait for it to complete first!\n"); + error = true; + } + else + { + if (code == 25) + { + FilePosition fPos = reprap.GetMove()->PausePrint(pausedMoveBuffer); // tell Move we wish to pause the current print + for (size_t drive = AXES; drive < DRIVES; ++drive) + { + pausedMoveBuffer[drive] = 0.0; // set extrusion to zero but leave positions and feed rate alone + } + if (fPos != noFilePosition) + { + fileBeingPrinted.Seek(fPos); // replay the abandoned instructions if/when we resume + } + fileGCode->Init(); + ClearMove(); + if (reprap.Debug(moduleGcodes)) + { + platform->Message(BOTH_MESSAGE, "Paused print, file offset=%u\n", fPos); + } + } + pausedFanValue = platform->GetFanValue(); + fractionOfFilePrinted = fileBeingPrinted.FractionRead(); + fileToPrint.MoveFrom(fileBeingPrinted); + fileGCode->Pause(); + state = GCodeState::pausing1; + isPaused = true; + } break; case 26: // Set SD position @@ -2366,7 +2455,7 @@ bool GCodes::HandleMcode(GCodeBuffer* gb) { for (int8_t extruder = AXES; extruder < DRIVES; extruder++) { - lastExtruderPosition[extruder - AXES] = 0.0; + lastRawExtruderPosition[extruder - AXES] = 0.0; } drivesRelative = false; } @@ -2377,7 +2466,7 @@ bool GCodes::HandleMcode(GCodeBuffer* gb) { for (int8_t extruder = AXES; extruder < DRIVES; extruder++) { - lastExtruderPosition[extruder - AXES] = 0.0; + lastRawExtruderPosition[extruder - AXES] = 0.0; } drivesRelative = true; } @@ -2393,6 +2482,7 @@ bool GCodes::HandleMcode(GCodeBuffer* gb) { return false; } + { // Save the current positions as we may need them later float positionNow[DRIVES]; @@ -2447,14 +2537,24 @@ bool GCodes::HandleMcode(GCodeBuffer* gb) break; case 98: // Call Macro/Subprogram + if (!AllMovesAreFinishedAndMoveBufferIsLoaded()) + { + return false; + } + if (gb->Seen('P')) { - result = DoFileMacro(gb->GetString()); + DoFileMacro(gb->GetString()); } break; case 99: // Return from Macro/Subprogram - result = FileMacroCyclesReturn(); + if (!AllMovesAreFinishedAndMoveBufferIsLoaded()) + { + return false; + } + + FileMacroCyclesReturn(); break; case 104: // Deprecated. This sets the active temperature of every heater of the active tool @@ -2479,16 +2579,24 @@ bool GCodes::HandleMcode(GCodeBuffer* gb) case 105: // Get Extruder Temperature / Get Status Message { int param = (gb->Seen('S')) ? gb->GetIValue() : 0; + int seq = (gb->Seen('R')) ? gb->GetIValue() : -1; switch (param) { + // case 1 is reserved for future Pronterface versions, see + // http://reprap.org/wiki/G-code#M105:_Get_Extruder_Temperature + case 2: - reprap.GetStatusResponse(reply, 2); // send JSON-formatted status response - reply.cat("\n"); + reprap.GetLegacyStatusResponse(reply, 2, seq); // send JSON-formatted status response break; + case 3: - reprap.GetStatusResponse(reply, 3); // send extended JSON-formatted response - reply.cat("\n"); + reprap.GetLegacyStatusResponse(reply, 3, seq); // send extended JSON-formatted response break; + + case 4: + reprap.GetStatusResponse(reply, 3, false); // send print status JSON-formatted response + break; + default: reply.copy("T:"); for(int8_t heater = 1; heater < HEATERS; heater++) @@ -2508,16 +2616,19 @@ bool GCodes::HandleMcode(GCodeBuffer* gb) case 106: // Set/report fan values { bool seen = false; - if (gb->Seen('I')) + + if (gb->Seen('I')) // Invert cooling { coolingInverted = (gb->GetIValue() > 0); seen = true; } - if (gb->Seen('S')) + + if (gb->Seen('S')) // Set new fan value { float f = gb->GetFValue(); f = min<float>(f, 255.0); f = max<float>(f, 0.0); + seen = true; if (coolingInverted) { // Check if 1.0 or 255.0 may be used as the maximum value @@ -2527,13 +2638,11 @@ bool GCodes::HandleMcode(GCodeBuffer* gb) { platform->SetFanValue(f); } - seen = true; } - - if (!seen) + else { - float fanValue = coolingInverted ? (1.0 - platform->GetFanValue()) : platform->GetFanValue(); - reply.printf("Fan value: %d%%, Cooling inverted: %s\n", (byte)(fanValue * 100.0), + float f = coolingInverted ? (1.0 - platform->GetFanValue()) : platform->GetFanValue(); + reply.printf("Fan value: %d%%, Cooling inverted: %s\n", (byte)(f * 100.0), coolingInverted ? "yes" : "no"); } } @@ -2544,7 +2653,10 @@ bool GCodes::HandleMcode(GCodeBuffer* gb) break; case 109: // Deprecated - if(gb->Seen('S')) + if (!AllMovesAreFinishedAndMoveBufferIsLoaded()) + return false; + + if (gb->Seen('S')) { float temperature = gb->GetFValue(); Tool *tool; @@ -2559,10 +2671,6 @@ bool GCodes::HandleMcode(GCodeBuffer* gb) tool = reprap.GetCurrentTool(); } SetToolHeaters(tool, temperature); - if (!AllMovesAreFinishedAndMoveBufferIsLoaded()) // tell Move not to wait for more moves - { - return false; - } result = ToolHeatersAtSetTemperatures(tool); } break; @@ -2635,7 +2743,7 @@ bool GCodes::HandleMcode(GCodeBuffer* gb) { reply.copy("Endstops - "); char comma = ','; - for(int8_t axis = 0; axis < AXES; axis++) + for (size_t axis = 0; axis < AXES; axis++) { const char* es; switch(platform->Stopped(axis)) @@ -2669,11 +2777,19 @@ bool GCodes::HandleMcode(GCodeBuffer* gb) break; case 120: - result = Push(); + if (!AllMovesAreFinishedAndMoveBufferIsLoaded()) + { + return false; + } + Push(); break; case 121: - result = Pop(); + if (!AllMovesAreFinishedAndMoveBufferIsLoaded()) + { + return false; + } + Pop(); break; case 122: @@ -2739,16 +2855,17 @@ bool GCodes::HandleMcode(GCodeBuffer* gb) // break; case 190: // Deprecated... + if (!AllMovesAreFinishedAndMoveBufferIsLoaded()) // tell Move not to wait for more moves + { + return false; + } + if (gb->Seen('S')) { if (HOT_BED >= 0) { reprap.GetHeat()->SetActiveTemperature(HOT_BED, gb->GetFValue()); reprap.GetHeat()->Activate(HOT_BED); - if (!AllMovesAreFinishedAndMoveBufferIsLoaded()) // tell Move not to wait for more moves - { - return false; - } result = reprap.GetHeat()->HeaterAtSetTemperature(HOT_BED); } } @@ -2772,7 +2889,7 @@ bool GCodes::HandleMcode(GCodeBuffer* gb) float eVals[DRIVES-AXES]; int eCount = DRIVES-AXES; gb->GetFloatArray(eVals, eCount); - for(int8_t e = 0; e < eCount; e++) + for (size_t e = 0; e < eCount; e++) { platform->SetAcceleration(AXES + e, eVals[e]*distanceScale); } @@ -2924,6 +3041,11 @@ bool GCodes::HandleMcode(GCodeBuffer* gb) speedFactorChange *= newSpeedFactor/speedFactor; speedFactor = newSpeedFactor; } + else + { + reply.printf("Invalid speed factor specified.\n"); + error = true; + } } else { @@ -2954,13 +3076,15 @@ bool GCodes::HandleMcode(GCodeBuffer* gb) } break; + // For case 226, see case 25 + case 300: // Beep if (gb->Seen('P')) { int ms = gb->GetIValue(); if (gb->Seen('S')) { - platform->Beep(gb->GetIValue(), ms); + reprap.Beep(gb->GetIValue(), ms); } } break; @@ -3039,18 +3163,18 @@ bool GCodes::HandleMcode(GCodeBuffer* gb) case 550: // Set/report machine name if (gb->Seen('P')) { - reprap.GetWebserver()->SetName(gb->GetString()); + reprap.SetName(gb->GetString()); } else { - reply.printf("RepRap name: %s\n", reprap.GetWebserver()->GetName()); + reply.printf("RepRap name: %s\n", reprap.GetName()); } break; case 551: // Set password (no option to report it) if (gb->Seen('P')) { - reprap.GetWebserver()->SetPassword(gb->GetString()); + reprap.SetPassword(gb->GetString()); } break; @@ -3648,116 +3772,46 @@ bool GCodes::HandleMcode(GCodeBuffer* gb) error = true; reply.printf("invalid M Code: %s\n", gb->Buffer()); } - if (result) + if (result && state == GCodeState::normal) { HandleReply(error, gb, reply.Pointer(), 'M', code, resend); } return result; } -bool GCodes::HandleTcode(GCodeBuffer* gb) +bool GCodes::HandleTcode(GCodeBuffer* gb, StringRef& reply) { - int code = gb->GetIValue(); - code += gb->GetToolNumberAdjust(); - if (simulating) + if (!AllMovesAreFinishedAndMoveBufferIsLoaded()) { - return true; // we don't yet simulate any T codes + return false; } - bool result = ChangeTool(code); - if (result) - { - HandleReply(false, gb, "", 'T', code, false); - } - return result; + newToolNumber = gb->GetIValue(); + newToolNumber += gb->GetToolNumberAdjust(); + if (simulating) // we don't yet simulate any T codes + { + HandleReply(false, gb, "", 'T', newToolNumber, false); + } + else + { + // If old and new are the same still follow the sequence - the user may want the macros run. + Tool *oldTool = reprap.GetCurrentTool(); + state = GCodeState::toolChange1; + if (oldTool != NULL) + { + scratchString.printf("tfree%d.g", oldTool->Number()); + DoFileMacro(scratchString.Pointer()); + } + } + return true; } // Return the amount of filament extruded -float GCodes::GetExtruderPosition(uint8_t extruder) const +float GCodes::GetRawExtruderPosition(size_t extruder) const { - return (extruder < (DRIVES - AXES)) ? lastExtruderPosition[extruder] : 0; + return (extruder < (DRIVES - AXES)) ? lastRawExtruderPosition[extruder] : 0; } -bool GCodes::ChangeTool(int newToolNumber) -{ - Tool* oldTool = reprap.GetCurrentTool(); - Tool* newTool = reprap.GetTool(newToolNumber); - - // If old and new are the same still follow the sequence - - // The user may want the macros run. - - switch(toolChangeSequence) - { - case 0: // Pre-release sequence for the old tool (if any) - if(oldTool != NULL) - { - scratchString.printf("tfree%d.g", oldTool->Number()); - if(DoFileMacro(scratchString.Pointer())) - { - toolChangeSequence++; - } - } - else - { - toolChangeSequence++; - } - return false; - - case 1: // Release the old tool (if any) - if(oldTool != NULL) - { - reprap.StandbyTool(oldTool->Number()); - } - toolChangeSequence++; - return false; - - case 2: // Run the pre-tool-change macro cycle for the new tool (if any) - if(newTool != NULL) - { - scratchString.printf("tpre%d.g", newToolNumber); - if(DoFileMacro(scratchString.Pointer())) - { - toolChangeSequence++; - } - } - else - { - toolChangeSequence++; - } - return false; - - case 3: // Select the new tool (even if it doesn't exist - that just deselects all tools) - reprap.SelectTool(newToolNumber); - toolChangeSequence++; - return false; - - case 4: // Run the post-tool-change macro cycle for the new tool (if any) - if(newTool != NULL) - { - scratchString.printf("tpost%d.g", newToolNumber); - if(DoFileMacro(scratchString.Pointer())) - { - toolChangeSequence++; - } - } - else - { - toolChangeSequence++; - } - return false; - - case 5: // All done - toolChangeSequence = 0; - return true; - - default: - platform->Message(BOTH_ERROR_MESSAGE, "Tool change - dud sequence number.\n"); - } - - toolChangeSequence = 0; - return true; -} - // Pause the current SD card print. Called from the web interface. void GCodes::PauseSDPrint() { @@ -3794,333 +3848,21 @@ void GCodes::SetPositions(float positionNow[DRIVES]) reprap.GetMove()->SetPositions(positionNow); } -//************************************************************************************* - -// This class stores a single G Code and provides functions to allow it to be parsed - -GCodeBuffer::GCodeBuffer(Platform* p, const char* id) -{ - platform = p; - identity = id; - writingFileDirectory = NULL; // Has to be done here as Init() is called every line. - toolNumberAdjust = 0; - checksumRequired = false; -} - -void GCodeBuffer::Init() -{ - gcodePointer = 0; - readPointer = -1; - inComment = false; - state = idle; -} - -int GCodeBuffer::CheckSum() const -{ - int cs = 0; - for (int i = 0; gcodeBuffer[i] != '*' && gcodeBuffer[i] != 0; i++) - { - cs = cs ^ gcodeBuffer[i]; - } - cs &= 0xff; // Defensive programming... - return cs; -} - -// Add a byte to the code being assembled. If false is returned, the code is -// not yet complete. If true, it is complete and ready to be acted upon. -bool GCodeBuffer::Put(char c) -{ - if (c == ';') - { - inComment = true; - } - else if (c == '\n' || !c) - { - gcodeBuffer[gcodePointer] = 0; - if (reprap.Debug(moduleGcodes) && gcodeBuffer[0] && !writingFileDirectory) // Don't bother with blank/comment lines - { - platform->Message(HOST_MESSAGE, "%s%s\n", identity, gcodeBuffer); - } - - // Deal with line numbers and checksums - if (Seen('*')) - { - int csSent = GetIValue(); - int csHere = CheckSum(); - Seen('N'); - if (csSent != csHere) - { - snprintf(gcodeBuffer, GCODE_LENGTH, "M998 P%d", GetIValue()); - Init(); - return true; - } - - // Strip out the line number and checksum - gcodePointer = 0; - while (gcodeBuffer[gcodePointer] != ' ' && gcodeBuffer[gcodePointer]) - { - gcodePointer++; - } - - // Anything there? - if (!gcodeBuffer[gcodePointer]) - { - // No... - gcodeBuffer[0] = 0; - Init(); - return false; - } - - // Yes... - gcodePointer++; - int gp2 = 0; - while (gcodeBuffer[gcodePointer] != '*' && gcodeBuffer[gcodePointer]) - { - gcodeBuffer[gp2] = gcodeBuffer[gcodePointer++]; - gp2++; - } - gcodeBuffer[gp2] = 0; - } - else if (checksumRequired) - { - gcodeBuffer[0] = 0; - Init(); - return false; - } - Init(); - return true; - } - else if (!inComment || writingFileDirectory) - { - gcodeBuffer[gcodePointer++] = c; - if (gcodePointer >= GCODE_LENGTH) - { - platform->Message(BOTH_ERROR_MESSAGE, "G-Code buffer length overflow.\n"); - gcodePointer = 0; - gcodeBuffer[0] = 0; - } - } - - return false; -} - -bool GCodeBuffer::Put(const char *str, size_t len) -{ - for(size_t i=0; i<=len; i++) - { - if (Put(str[i])) - { - return true; - } - } - - return false; -} - -// Does this buffer contain any code? - -bool GCodeBuffer::IsEmpty() const -{ - const char *buf = gcodeBuffer; - while (strchr(" \t\n\r", *buf)) - { - if (*buf == 0) - { - return true; - } - buf++; - } - return false; -} - -// Is 'c' in the G Code string? -// Leave the pointer there for a subsequent read. - -bool GCodeBuffer::Seen(char c) -{ - readPointer = 0; - for (;;) - { - char b = gcodeBuffer[readPointer]; - if (b == 0 || b == ';') break; - if (b == c) return true; - ++readPointer; - } - readPointer = -1; - return false; -} - -// Get a float after a G Code letter found by a call to Seen() - -float GCodeBuffer::GetFValue() +bool GCodes::IsPaused() const { - if (readPointer < 0) - { - platform->Message(BOTH_ERROR_MESSAGE, "GCodes: Attempt to read a GCode float before a search.\n"); - readPointer = -1; - return 0.0; - } - float result = (float) strtod(&gcodeBuffer[readPointer + 1], 0); - readPointer = -1; - return result; + return isPaused && !IsPausing() && !IsResuming(); } -// Get a :-separated list of floats after a key letter - -const void GCodeBuffer::GetFloatArray(float a[], int& returnedLength) +bool GCodes::IsPausing() const { - int length = 0; - if(readPointer < 0) - { - platform->Message(BOTH_ERROR_MESSAGE, "GCodes: Attempt to read a GCode float array before a search.\n"); - readPointer = -1; - returnedLength = 0; - return; - } - - bool inList = true; - while(inList) - { - if(length >= returnedLength) // Array limit has been set in here - { - platform->Message(BOTH_ERROR_MESSAGE, "GCodes: Attempt to read a GCode float array that is too long: %s\n", gcodeBuffer); - readPointer = -1; - returnedLength = 0; - return; - } - a[length] = (float)strtod(&gcodeBuffer[readPointer + 1], 0); - length++; - readPointer++; - while(gcodeBuffer[readPointer] && (gcodeBuffer[readPointer] != ' ') && (gcodeBuffer[readPointer] != LIST_SEPARATOR)) - { - readPointer++; - } - if(gcodeBuffer[readPointer] != LIST_SEPARATOR) - { - inList = false; - } - } - - // Special case if there is one entry and returnedLength requests several. - // Fill the array with the first entry. - - if(length == 1 && returnedLength > 1) - { - for(int8_t i = 1; i < returnedLength; i++) - { - a[i] = a[0]; - } - } - else - { - returnedLength = length; - } - - readPointer = -1; + return state == GCodeState::pausing1 || state == GCodeState::pausing2 + || (stackPointer != 0 && (stack[0].state == GCodeState::pausing1 || stack[0].state == GCodeState::pausing2)); } -// Get a :-separated list of longs after a key letter - -const void GCodeBuffer::GetLongArray(long l[], int& returnedLength) +bool GCodes::IsResuming() const { - int length = 0; - if(readPointer < 0) - { - platform->Message(BOTH_ERROR_MESSAGE, "GCodes: Attempt to read a GCode long array before a search.\n"); - readPointer = -1; - return; - } - - bool inList = true; - while(inList) - { - if(length >= returnedLength) // Array limit has been set in here - { - platform->Message(BOTH_ERROR_MESSAGE, "GCodes: Attempt to read a GCode long array that is too long: %s\n", gcodeBuffer); - readPointer = -1; - returnedLength = 0; - return; - } - l[length] = strtol(&gcodeBuffer[readPointer + 1], 0, 0); - length++; - readPointer++; - while(gcodeBuffer[readPointer] && (gcodeBuffer[readPointer] != ' ') && (gcodeBuffer[readPointer] != LIST_SEPARATOR)) - { - readPointer++; - } - if(gcodeBuffer[readPointer] != LIST_SEPARATOR) - { - inList = false; - } - } - returnedLength = length; - readPointer = -1; -} - -// Get a string after a G Code letter found by a call to Seen(). -// It will be the whole of the rest of the GCode string, so strings -// should always be the last parameter. - -const char* GCodeBuffer::GetString() -{ - if (readPointer < 0) - { - platform->Message(BOTH_ERROR_MESSAGE, "GCodes: Attempt to read a GCode string before a search.\n"); - readPointer = -1; - return ""; - } - const char* result = &gcodeBuffer[readPointer + 1]; - readPointer = -1; - return result; -} - -// This returns a pointer to the end of the buffer where a -// string starts. It assumes that an M or G search has -// been done followed by a GetIValue(), so readPointer will -// be -1. It absorbs "M/Gnnn " (including the space) from the -// start and returns a pointer to the next location. - -// This is provided for legacy use, in particular in the M23 -// command that sets the name of a file to be printed. In -// preference use GetString() which requires the string to have -// been preceded by a tag letter. - -const char* GCodeBuffer::GetUnprecedentedString(bool optional) -{ - readPointer = 0; - while (gcodeBuffer[readPointer] && gcodeBuffer[readPointer] != ' ') - { - readPointer++; - } - - if (!gcodeBuffer[readPointer]) - { - readPointer = -1; - if (optional) - { - return NULL; - } - platform->Message(BOTH_ERROR_MESSAGE, "GCodes: String expected but not seen.\n"); - return gcodeBuffer; // Good idea? - } - - const char* result = &gcodeBuffer[readPointer + 1]; - readPointer = -1; - return result; -} - -// Get an long after a G Code letter - -long GCodeBuffer::GetLValue() -{ - if (readPointer < 0) - { - platform->Message(BOTH_ERROR_MESSAGE, "GCodes: Attempt to read a GCode int before a search.\n"); - readPointer = -1; - return 0; - } - long result = strtol(&gcodeBuffer[readPointer + 1], 0, 0); - readPointer = -1; - return result; + return state == GCodeState::resuming1 + || (stackPointer != 0 && stack[0].state == GCodeState::resuming1); } +// End @@ -22,8 +22,9 @@ Licence: GPL #ifndef GCODES_H #define GCODES_H -#define STACK 5 -#define GCODE_LENGTH 100 // Maximum length of internally-generated G Code string +#include "GCodeBuffer.h" + +const unsigned int StackSize = 5; const char feedrateLetter = 'F'; // GCode feedrate const char extrudeLetter = 'E'; // GCode extrude @@ -32,55 +33,34 @@ const char extrudeLetter = 'E'; // GCode extrude typedef uint16_t EndstopChecks; // must be large enough to hold a bitmap of drive numbers or ZProbeActive const EndstopChecks ZProbeActive = 1 << 15; // must be distinct from 1 << (any drive number) -// Small class to hold an individual GCode and provide functions to allow it to be parsed -class GCodeBuffer -{ - public: - GCodeBuffer(Platform* p, const char* id); - void Init(); // Set it up - bool Put(char c); // Add a character to the end - bool Put(const char *str, size_t len); // Add an entire string - bool IsEmpty() const; // Does this buffer contain any code? - bool Seen(char c); // Is a character present? - float GetFValue(); // Get a float after a key letter - int GetIValue(); // Get an integer after a key letter - long GetLValue(); // Get a long integer after a key letter - const char* GetUnprecedentedString(bool optional = false); // Get a string with no preceding key letter - const char* GetString(); // Get a string after a key letter - const void GetFloatArray(float a[], int& length); // Get a :-separated list of floats after a key letter - const void GetLongArray(long l[], int& length); // Get a :-separated list of longs after a key letter - const char* Buffer() const; - bool Active() const; - void SetFinished(bool f); // Set the G Code executed (or not) - void Pause(); - void CancelPause(); - void Resume(); - const char* WritingFileDirectory() const; // If we are writing the G Code to a file, where that file is - void SetWritingFileDirectory(const char* wfd); // Set the directory for the file to write the GCode in - int GetToolNumberAdjust() const { return toolNumberAdjust; } - void SetToolNumberAdjust(int arg) { toolNumberAdjust = arg; } - void SetCommsProperties(uint32_t arg) { checksumRequired = (arg & 1); } - - private: +const float minutesToSeconds = 60.0; +const float secondsToMinutes = 1.0/minutesToSeconds; - enum State { idle, executing, paused }; - int CheckSum() const; // Compute the checksum (if any) at the end of the G Code - Platform* platform; // Pointer to the RepRap's controlling class - char gcodeBuffer[GCODE_LENGTH]; // The G Code - const char* identity; // Where we are from (web, file, serial line etc) - int gcodePointer; // Index in the buffer - int readPointer; // Where in the buffer to read next - bool inComment; // Are we after a ';' character? - bool checksumRequired; // True if we only accept commands with a valid checksum - State state; // Idle, executing or paused - const char* writingFileDirectory; // If the G Code is going into a file, where that is - int toolNumberAdjust; // The adjustment to tool numbers in commands we receive +// Enumeration to list all the possible states that the Gcode processing machine may be in +enum class GCodeState +{ + normal, // not doing anything and ready to process a new GCode + waitingForMoveToComplete, // doing a homing move, so we must wait for it to finish before processing another GCode + homing, + setBed1, + setBed2, + setBed3, + toolChange1, + toolChange2, + toolChange3, + pausing1, + pausing2, + resuming1, + resuming2, + resuming3 }; // Small class to stack the state when we execute a macro file class GCodeMachineState { public: + GCodeState state; + GCodeBuffer *gb; // this may be null when executing config.g float feedrate; FileData fileState; bool drivesRelative; @@ -101,56 +81,63 @@ class GCodes void Init(); // Set it up void Exit(); // Shut it down void Reset(); // Reset some parameter to defaults - bool RunConfigurationGCodes(); // Run the configuration G Code file on reboot - bool ReadMove(float* m, EndstopChecks& ce, bool& noDeltaMapping); // Called by the Move class to get a movement set by the last G Code + bool ReadMove(float* m, EndstopChecks& ce, bool& noDeltaMapping, FilePosition& fPos); // Called by the Move class to get a movement set by the last G Code + void ClearMove(); void QueueFileToPrint(const char* fileName); // Open a file of G Codes to run void DeleteFile(const char* fileName); // Does what it says bool GetProbeCoordinates(int count, float& x, float& y, float& z) const; // Get pre-recorded probe coordinates - void GetCurrentCoordinates(StringRef& s) const; // Write where we are into a string + void GetCurrentCoordinates(StringRef& s) const; // Write where we are into a string bool PrintingAFile() const; // Are we in the middle of printing a file? + bool DoingFileMacro() const; // Or still busy processing a macro file? float FractionOfFilePrinted() const; // Get fraction of file printed void Diagnostics(); // Send helpful information out bool HaveIncomingData() const; // Is there something that we have to do? bool GetAxisIsHomed(uint8_t axis) const { return axisIsHomed[axis]; } // Is the axis at 0? void SetAxisIsHomed(uint8_t axis) { axisIsHomed[axis] = true; } // Tell us that the axis is now homed bool CoolingInverted() const; // Is the current fan value inverted? - float GetExtruderPosition(uint8_t extruder) const; // Get the amount of filament extruded + void PauseSDPrint(); // Pause the current print from SD card - float GetSpeedFactor() const { return speedFactor * 60.0; } // Return the current speed factor + float GetSpeedFactor() const { return speedFactor * minutesToSeconds; } // Return the current speed factor const float *GetExtrusionFactors() const { return extrusionFactors; } // Return the current extrusion factors + float GetRawExtruderPosition(size_t drive) const; // Get the actual extruder position, after adjusting the extrusion factor + bool HaveAux() const { return auxDetected; } // Any device on the AUX line? + + bool IsPaused() const; + bool IsPausing() const; + bool IsResuming() const; + private: - void DoFilePrint(GCodeBuffer* gb); // Get G Codes from a file and print them + void StartNextGCode(StringRef& reply); // Fetch a new GCode and process it + void DoFilePrint(GCodeBuffer* gb, StringRef& reply); // Get G Codes from a file and print them bool AllMovesAreFinishedAndMoveBufferIsLoaded(); // Wait for move queue to exhaust and the current position is loaded bool DoCannedCycleMove(EndstopChecks ce); // Do a move from an internally programmed canned cycle - bool DoFileMacro(const char* fileName); // Run a GCode macro in a file - bool FileMacroCyclesReturn(); // End a macro - bool ActOnCode(GCodeBuffer* gb); // Do a G, M or T Code - bool HandleGcode(GCodeBuffer* gb); // Do a G code - bool HandleMcode(GCodeBuffer* gb); // Do an M code - bool HandleTcode(GCodeBuffer* gb); // Do a T code + void DoFileMacro(const char* fileName); // Run a GCode macro in a file, error if not found + void FileMacroCyclesReturn(); // End a macro + bool ActOnCode(GCodeBuffer* gb, StringRef& reply); // Do a G, M or T Code + bool HandleGcode(GCodeBuffer* gb, StringRef& reply); // Do a G code + bool HandleMcode(GCodeBuffer* gb, StringRef& reply); // Do an M code + bool HandleTcode(GCodeBuffer* gb, StringRef& reply); // Do a T code int SetUpMove(GCodeBuffer* gb, StringRef& reply); // Pass a move on to the Move module bool DoDwell(GCodeBuffer *gb); // Wait for a bit bool DoDwellTime(float dwell); // Really wait for a bit - bool HomeCartesian(StringRef& reply, bool& error); // Home some axes - bool HomeDelta(StringRef& reply, bool& error); // Home the printer bool DoSingleZProbeAtPoint(int probePointIndex); // Probe at a given point bool DoSingleZProbe(); // Probe where we are bool SetSingleZProbeAtAPosition(GCodeBuffer *gb, StringRef& reply); // Probes at a given position - see the comment at the head of the function itself - bool SetBedEquationWithProbe(int sParam, StringRef& reply); // Probes a series of points and sets the bed equation + void SetBedEquationWithProbe(int sParam, StringRef& reply); // Probes a series of points and sets the bed equation bool SetPrintZProbe(GCodeBuffer *gb, StringRef& reply); // Either return the probe value, or set its threshold void SetOrReportOffsets(StringRef& reply, GCodeBuffer *gb); // Deal with a G10 bool SetPositions(GCodeBuffer *gb); // Deal with a G92 bool LoadMoveBufferFromGCode(GCodeBuffer *gb, // Set up a move for the Move class bool doingG92, bool applyLimits); bool NoHome() const; // Are we homing and not finished? - bool Push(); // Push feedrate etc on the stack - bool Pop(); // Pop feedrate etc + void Push(); // Push feedrate etc on the stack + void Pop(); // Pop feedrate etc void DisableDrives(); // Turn the motors off void SetEthernetAddress(GCodeBuffer *gb, int mCode); // Does what it says void SetMACAddress(GCodeBuffer *gb); // Deals with an M540 - void HandleReply(bool error, const GCodeBuffer *gb, // If the GCode is from the serial interface, reply to it + void HandleReply(bool error, const GCodeBuffer *gb, // If the GCode is from the serial interface, reply to it const char* reply, char gMOrT, int code, bool resend); bool OpenFileToWrite(const char* directory, // Start saving GCodes in a file const char* fileName, GCodeBuffer *gb); @@ -163,7 +150,6 @@ class GCodes int8_t Heater(int8_t head) const; // Legacy G codes start heaters at 0, but we use 0 for the bed. This sorts that out. void AddNewTool(GCodeBuffer *gb, StringRef& reply); // Create a new tool definition void SetToolHeaters(Tool *tool, float temperature); // Set all a tool's heaters to the temperature. For M104... - bool ChangeTool(int newToolNumber); // Select a new tool bool ToolHeatersAtSetTemperatures(const Tool *tool) const; // Wait for the heaters associated with the specified tool to reach their set temperatures bool AllAxesAreHomed() const; // Return true if all axes are homed void SetAllAxesNotHomed(); // Flag all axes as not homed @@ -171,6 +157,7 @@ class GCodes Platform* platform; // The RepRap machine bool active; // Live and running? + bool isPaused; // true if the print has been paused Webserver* webserver; // The webserver class float dwellTime; // How long a pause for a dwell (seconds)? bool dwellWaiting; // We are in a dwell @@ -179,17 +166,20 @@ class GCodes GCodeBuffer* serialGCode; // ... GCodeBuffer* auxGCode; // this one is for the LCD display on the async serial interface GCodeBuffer* fileMacroGCode; // ... + GCodeBuffer *gbCurrent; bool moveAvailable; // Have we seen a move G Code and set it up? float moveBuffer[DRIVES+1]; // Move coordinates; last is feed rate float savedMoveBuffer[DRIVES+1]; // The position and feedrate when we started the current simulation + float pausedMoveBuffer[DRIVES+1]; // Move coordinates; last is feed rate EndstopChecks endStopsToCheck; // Which end stops we check them on the next move bool disableDeltaMapping; // True if delta mapping should be bypassed for the next move - bool drivesRelative; // Are movements relative - all except X, Y and Z - bool axesRelative; // Are movements relative - X, Y and Z - GCodeMachineState stack[STACK]; // State that we save when calling macro files + GCodeState state; // The main state variable of the GCode state machine + bool drivesRelative; + bool axesRelative; + GCodeMachineState stack[StackSize]; // State that we save when calling macro files unsigned int stackPointer; // Push and Pop stack pointer static const char axisLetters[AXES]; // 'X', 'Y', 'Z' - float lastExtruderPosition[DRIVES - AXES]; // Extruder position of the last move fed into the Move class + float lastRawExtruderPosition[DRIVES - AXES]; // Extruder position of the last move fed into the Move class float record[DRIVES+1]; // Temporary store for move positions float moveToDo[DRIVES+1]; // Where to go set by G1 etc bool activeDrive[DRIVES+1]; // Is this drive involved in a move? @@ -199,15 +189,13 @@ class GCodes FileData fileToPrint; FileStore* fileBeingWritten; // A file to write G Codes (or sometimes HTML) in FileStore* configFile; // A file containing a macro + uint16_t toBeHomed; // Bitmap of axes still to be homed bool doingFileMacro; // Are we executing a macro file? + int oldToolNumber, newToolNumber; // Tools being changed float fractionOfFilePrinted; // Only used to record the main file when a macro is being printed const char* eofString; // What's at the end of an HTML file? uint8_t eofStringCounter; // Check the... uint8_t eofStringLength; // ... EoF string as we read. - bool homing; // Are we homing any axes? - bool homeX; // True to home the X axis this move - bool homeY; // True to home the Y axis this move - bool homeZ; // True to home the Z axis this move int probeCount; // Counts multiple probe points int8_t cannedCycleMoveCount; // Counts through internal (i.e. not macro) canned cycle moves bool cannedCycleMoveQueued; // True if a canned cycle move has been set @@ -215,78 +203,22 @@ class GCodes float longWait; // Timer for things that happen occasionally (seconds) bool limitAxes; // Don't think outside the box. bool axisIsHomed[AXES]; // These record which of the axes have been homed - bool waitingForMoveToComplete; bool coolingInverted; + float pausedFanValue; float speedFactor; // speed factor, including the conversion from mm/min to mm/sec, normally 1/60 float speedFactorChange; // factor by which we changed the speed factor since the last move float extrusionFactors[DRIVES - AXES]; // extrusion factors (normally 1.0) float lastProbedZ; // the last height at which the Z probe stopped - uint8_t toolChangeSequence; // Steps through the tool change procedure - uint8_t setBedState; // Steps through the setbed procedure + bool auxDetected; // Have we processed at least one G-Code from an AUX device? bool simulating; float simulationTime; + FilePosition filePos; // The position we got up to in the file being printed + FilePosition moveFilePos; // Saved version of filePos for the next real move to be processed }; //***************************************************************************************************** -// Get an Int after a G Code letter - -inline int GCodeBuffer::GetIValue() -{ - return (int)GetLValue(); -} - -inline const char* GCodeBuffer::Buffer() const -{ - return gcodeBuffer; -} - -inline bool GCodeBuffer::Active() const -{ - return state == executing; -} - -inline void GCodeBuffer::SetFinished(bool f) -{ - state = (f) ? idle : executing; -} - -inline void GCodeBuffer::Pause() -{ - if (state == executing) - { - state = paused; - } -} - -// If we paused a print, cancel printing that file and get ready to print a new one -inline void GCodeBuffer::CancelPause() -{ - if (state == paused) - { - Init(); - } -} - -inline void GCodeBuffer::Resume() -{ - if (state == paused) - { - state = executing; - } -} - -inline const char* GCodeBuffer::WritingFileDirectory() const -{ - return writingFileDirectory; -} - -inline void GCodeBuffer::SetWritingFileDirectory(const char* wfd) -{ - writingFileDirectory = wfd; -} - inline float GCodes::FractionOfFilePrinted() const { if (fractionOfFilePrinted < 0.0) @@ -307,6 +239,11 @@ inline bool GCodes::PrintingAFile() const return FractionOfFilePrinted() >= 0.0; } +inline bool GCodes::DoingFileMacro() const +{ + return doingFileMacro; +} + inline bool GCodes::HaveIncomingData() const { return fileBeingPrinted.IsLive() || @@ -315,27 +252,12 @@ inline bool GCodes::HaveIncomingData() const (platform->GetAux()->Status() & byteAvailable); } -inline bool GCodes::NoHome() const -{ - return !(homeX || homeY || homeZ); -} - -// This function takes care of the fact that the heater and head indices -// don't match because the bed is heater 0. - +// This function takes care of the fact that the heater and head indices don't match because the bed is heater 0. inline int8_t GCodes::Heater(int8_t head) const { return head+1; } -// Run the configuration G Code file to set up the machine. Usually just called once -// on re-boot. - -inline bool GCodes::RunConfigurationGCodes() -{ - return !DoFileMacro(platform->GetConfigFile()); -} - inline bool GCodes::CoolingInverted() const { return coolingInverted; @@ -63,7 +63,7 @@ void Heat::Spin() { pids[heater]->Spin(); } - platform->ClassReport("Heat", longWait, moduleHeat); + platform->ClassReport(longWait); } void Heat::Diagnostics() @@ -169,8 +169,8 @@ void Move::Init() xRectangle = 1.0/(0.8*reprap.GetPlatform()->AxisMaximum(X_AXIS)); yRectangle = xRectangle; - lastTime = reprap.GetPlatform()->Time(); - longWait = lastTime; + longWait = reprap.GetPlatform()->Time(); + idleCount = 0; simulating = false; simulationTime = 0.0; @@ -191,8 +191,12 @@ void Move::Spin() return; } + if (idleCount < 1000) + { + ++idleCount; + } + // See if we can add another move to the ring - bool moveAdded = false; if (!addNoMoreMoves && ddaRingAddPointer->GetState() == DDA::empty) { if (reprap.Debug(moduleMove)) @@ -203,24 +207,25 @@ void Move::Spin() float nextMove[DRIVES + 1]; EndstopChecks endStopsToCheck; bool noDeltaMapping; - if (reprap.GetGCodes()->ReadMove(nextMove, endStopsToCheck, noDeltaMapping)) + FilePosition filePos; + if (reprap.GetGCodes()->ReadMove(nextMove, endStopsToCheck, noDeltaMapping, filePos)) { currentFeedrate = nextMove[DRIVES]; // might be G1 with just an F field if (!noDeltaMapping || !IsDeltaMode()) { Transform(nextMove); } - if (ddaRingAddPointer->Init(nextMove, endStopsToCheck, IsDeltaMode() && !noDeltaMapping)) + if (ddaRingAddPointer->Init(nextMove, endStopsToCheck, IsDeltaMode() && !noDeltaMapping, filePos)) { ddaRingAddPointer = ddaRingAddPointer->GetNext(); - moveAdded = true; + idleCount = 0; } } } if (simulating) { - if (!moveAdded && !DDARingEmpty()) + if (idleCount > 10 && !DDARingEmpty()) { // No move added this time, so simulate executing one already in the queue DDA *dda = ddaRingGetPointer; @@ -233,21 +238,24 @@ void Move::Spin() else { // See whether we need to kick off a move - DDA *cdda = currentDda; // currentDda is volatile, so copy it + DDA *cdda = currentDda; // currentDda is volatile, so copy it if (cdda == nullptr) { // No DDA is executing, so start executing a new one if possible - DDA *dda = ddaRingGetPointer; - if (dda->GetState() == DDA::provisional) - { - dda->Prepare(); - } - cpu_irq_disable(); // must call StartNextMove and Interrupt with interrupts disabled - if (StartNextMove(Platform::GetInterruptClocks())) // start the next move if none is executing already + if (idleCount > 10) // better to have a few moves in the queue so that we can do lookahead { - Interrupt(); + DDA *dda = ddaRingGetPointer; + if (dda->GetState() == DDA::provisional) + { + dda->Prepare(); + } + cpu_irq_disable(); // must call StartNextMove and Interrupt with interrupts disabled + if (StartNextMove(Platform::GetInterruptClocks())) // start the next move if none is executing already + { + Interrupt(); + } + cpu_irq_enable(); } - cpu_irq_enable(); } else { @@ -271,7 +279,82 @@ void Move::Spin() } } - reprap.GetPlatform()->ClassReport("Move", longWait, moduleMove); + reprap.GetPlatform()->ClassReport(longWait); +} + +// Pause the print as soon as we can. +// Return the file position of the first queue move we are going to skip, or noFilePosition we we are not skipping any moves. +// If we skipped any moves then we update 'positions' to the positions and feed rate expected for the next move, else we leave them alone. +FilePosition Move::PausePrint(float positions[DRIVES+1]) +{ + // Find a move we can pause after. + // Ideally, we would adjust a move if necessary and possible so that we can pause after it, but for now we don't do that. + // There are a few possibilities: + // 1. There are no moves in the queue. + // 2. There is a currently-executing move, and possibly some more in the queue. + // 3. There are moves in the queue, but we haven't started executing them yet. Unlikely, but possible. + + const DDA *savedDdaRingAddPointer = ddaRingAddPointer; + + // First, see if there is a currently-executing move, and if so, whether we can safely pause at the end of it + cpu_irq_disable(); + DDA *dda = currentDda; + if (dda != nullptr) + { + if (dda->CanPause()) + { + ddaRingAddPointer = dda->GetNext(); + } + else + { + // We can't safely pause after the currently-executing move because its end speed is too high so we may miss steps. + // Search for the next move that we can safely stop after. + dda = ddaRingGetPointer; + while (dda != ddaRingAddPointer) + { + if (dda->CanPause()) + { + ddaRingAddPointer = dda->GetNext(); + break; + } + dda = dda->GetNext(); + } + } + } + else + { + ddaRingAddPointer = ddaRingGetPointer; + } + cpu_irq_enable(); + + FilePosition fPos = noFilePosition; + if (ddaRingAddPointer != savedDdaRingAddPointer) + { + // We are going to skip some moves. dda points to the last move we are going to print. + for (size_t axis = 0; axis < AXES; ++axis) + { + positions[axis] = dda->GetEndCoordinate(axis, false); + } + positions[DRIVES] = dda->GetRequestedSpeed(); + + dda = ddaRingAddPointer; + do + { + if (fPos == noFilePosition) + { + fPos = dda->GetFilePosition(); + } + dda->Release(); + dda = dda->GetNext(); + } + while (dda != savedDdaRingAddPointer); + } + else + { + GetCurrentUserPosition(positions, false); + } + + return fPos; } uint32_t maxStepTime=0, maxCalcTime=0, minCalcTime = 999, maxReps = 0; @@ -128,6 +128,9 @@ public: float GetSimulationTime() const { return simulationTime; } // Get the accumulated simulation time void PrintCurrentDda() const; // For debugging + FilePosition PausePrint(float positions[DRIVES+1]); // Pause the print as soon as we can + bool NoLiveMovement() const; // Is a move running, or are there any queued? + static int32_t MotorEndPointToMachine(size_t drive, float coord); // Convert a single motor position to number of steps static float MotorEndpointToPosition(int32_t endpoint, size_t drive); // Convert number of motor steps to motor position @@ -146,20 +149,17 @@ private: bool DDARingAdd(); // Add a processed look-ahead entry to the DDA ring DDA* DDARingGet(); // Get the next DDA ring entry to be run bool DDARingEmpty() const; // Anything there? - bool NoLiveMovement() const; // Is a move running, or are there any queued? void InverseDeltaTransform(const int32_t motorPos[AXES], float machinePos[AXES]) const; // Convert axis motor coordinates to Cartesian - // These implement the movement list - DDA* volatile currentDda; DDA* ddaRingAddPointer; DDA* volatile ddaRingGetPointer; - float lastTime; // The last time we were called (secs) bool addNoMoreMoves; // If true, allow no more moves to be added to the look-ahead bool active; // Are we live and running? bool simulating; // Are we simulating, or really printing? + unsigned int idleCount; // The number of times Spin was called and had no new moves to process float simulationTime; // Print time since we started simulating float currentFeedrate; // Err... the current feed rate... volatile float liveCoordinates[DRIVES]; // The endpoint that the machine moved to in the last completed move diff --git a/Network.cpp b/Network.cpp index 91bf2daf..4c9b35a5 100644 --- a/Network.cpp +++ b/Network.cpp @@ -39,14 +39,15 @@ ****************************************************************************************************/ #include "RepRapFirmware.h" -#include "DueFlashStorage.h" #include "ethernet_sam.h" +#ifdef LWIP_STATS +#include "lwip/src/include/lwip/stats.h" +#endif + extern "C" { #include "lwipopts.h" -#include "lwip/src/include/lwip/debug.h" -#include "lwip/src/include/lwip/stats.h" #include "lwip/src/include/lwip/tcp.h" void RepRapNetworkSetMACAddress(const u8_t macAddress[]); @@ -59,22 +60,22 @@ static tcp_pcb *telnet_pcb = NULL; static bool closingDataPort = false; -static uint8_t volatile inLwip = 0; +static volatile bool lwipLocked = false; static NetworkTransaction *sendingTransaction = NULL; static char sendingWindow[TCP_WND]; static uint16_t sendingWindowSize, sentDataOutstanding; static uint8_t sendingRetries; -// Called to put out a message via the RepRap firmware. -// Can be called from C as well as C++ +// Called only by LWIP to put out a message. +// May be called from C as well as C++ extern "C" void RepRapNetworkMessage(const char* s) { #ifdef LWIP_DEBUG - reprap.GetPlatform()->Message(DEBUG_MESSAGE, s); + reprap.GetPlatform()->Message(DEBUG_MESSAGE, "%s", s); #else - reprap.GetPlatform()->Message(HOST_MESSAGE, s); + reprap.GetPlatform()->Message(HOST_MESSAGE, "%s", s); #endif } @@ -83,39 +84,48 @@ extern "C" void RepRapNetworkMessage(const char* s) extern "C" { -// Callback functions for the EMAC driver +// Lock functions for LWIP (LWIP generally isn't thread-safe) +bool LockLWIP() +{ + if (lwipLocked) + return false; + + lwipLocked = true; + return true; +} + +void UnlockLWIP() +{ + lwipLocked = false; +} + +// Callback functions for the EMAC driver (called from ISR) static void emac_read_packet(uint32_t ul_status) { // Because the LWIP stack can become corrupted if we work with it in parallel, // we may have to wait for the next Spin() call to read the next packet. - // On this occasion, we can set the RX callback again. - if (inLwip) - { - reprap.GetNetwork()->ReadPacket(); - ethernet_set_rx_callback(NULL); - } - else + + if (LockLWIP()) { - ++inLwip; do { // read all queued packets from the RX buffer } while (ethernet_read()); - --inLwip; + UnlockLWIP(); + } + else + { + reprap.GetNetwork()->ReadPacket(); + ethernet_set_rx_callback(NULL); } } -// Callback functions called by LWIP +// Callback functions called by LWIP (may be called from ISR) static void conn_err(void *arg, err_t err) { // Report the error to the monitor - RepRapNetworkMessage("Network connection error, code "); - { - char tempBuf[10]; - snprintf(tempBuf, ARRAY_SIZE(tempBuf), "%d\n", err); - RepRapNetworkMessage(tempBuf); - } + reprap.GetPlatform()->Message(HOST_MESSAGE, "Network: Connection error, code %d\n", err); ConnectionState *cs = (ConnectionState*)arg; if (cs != NULL) @@ -136,17 +146,29 @@ static err_t conn_poll(void *arg, tcp_pcb *pcb) ConnectionState *cs = (ConnectionState*)arg; if (cs != NULL && sendingTransaction != NULL && cs == sendingTransaction->GetConnection()) { + // We tried to send data, but didn't receive an ACK within reasonable time. + sendingRetries++; if (sendingRetries == 4) { - RepRapNetworkMessage("poll received error!\n"); - + reprap.GetPlatform()->Message(HOST_MESSAGE, "Network: Poll received error!\n"); tcp_abort(pcb); return ERR_ABRT; } - tcp_write(pcb, sendingWindow + (sendingWindowSize - sentDataOutstanding), sentDataOutstanding, 0); - tcp_output(pcb); + // Try to send the remaining data once again + + err_t err = tcp_write(pcb, sendingWindow + (sendingWindowSize - sentDataOutstanding), sentDataOutstanding, 0); + if (err == ERR_OK) + { + tcp_output(pcb); + } + else + { + reprap.GetPlatform()->Message(HOST_MESSAGE, "Network: tcp_write in conn_poll failed with code %d\n", err); + tcp_abort(pcb); + return ERR_ABRT; + } } return ERR_OK; @@ -156,6 +178,8 @@ static err_t conn_poll(void *arg, tcp_pcb *pcb) static err_t conn_sent(void *arg, tcp_pcb *pcb, u16_t len) { + LWIP_UNUSED_ARG(pcb); + ConnectionState *cs = (ConnectionState*)arg; if (cs != NULL) { @@ -173,7 +197,7 @@ static err_t conn_recv(void *arg, tcp_pcb *pcb, pbuf *p, err_t err) { if (cs->pcb != pcb) { - RepRapNetworkMessage("Network: mismatched pcb\n"); + reprap.GetPlatform()->Message(HOST_MESSAGE, "Network: Mismatched pcb!\n"); tcp_abort(pcb); return ERR_ABRT; } @@ -182,16 +206,6 @@ static err_t conn_recv(void *arg, tcp_pcb *pcb, pbuf *p, err_t err) { // Tell higher levels that we are receiving data reprap.GetNetwork()->ReceiveInput(p, cs); -#if 0 //debug - { - char buff[20]; - strncpy(buff, (const char*)(p->payload), 18); - buff[18] = '\n'; - buff[19] = 0; - RepRapNetworkMessage("Network: Accepted data: "); - RepRapNetworkMessage(buff); - } -#endif } else if (cs->persistConnection) { @@ -263,7 +277,7 @@ void httpd_init() httpInitCount++; if (httpInitCount > 1) { - RepRapNetworkMessage("httpd_init() called more than once.\n"); + reprap.GetPlatform()->Message(HOST_MESSAGE, "httpd_init() called more than once.\n"); } tcp_pcb* pcb = tcp_new(); @@ -279,7 +293,7 @@ void ftpd_init() ftpInitCount++; if (ftpInitCount > 1) { - RepRapNetworkMessage("ftpd_init() called more than once.\n"); + reprap.GetPlatform()->Message(HOST_MESSAGE, "ftpd_init() called more than once.\n"); } tcp_pcb* pcb = tcp_new(); @@ -295,7 +309,7 @@ void telnetd_init() telnetInitCount++; if (telnetInitCount > 1) { - RepRapNetworkMessage("telnetd_init() called more than once.\n"); + reprap.GetPlatform()->Message(HOST_MESSAGE, "telnetd_init() called more than once.\n"); } tcp_pcb* pcb = tcp_new(); @@ -308,8 +322,8 @@ void telnetd_init() // Network/Ethernet class -Network::Network() - : isEnabled(true), state(NetworkInactive), readingData(false), +Network::Network(Platform* p) + : platform(p), isEnabled(true), state(NetworkInactive), readingData(false), freeTransactions(NULL), readyTransactions(NULL), writingTransactions(NULL), dataCs(NULL), ftpCs(NULL), telnetCs(NULL), freeSendBuffers(NULL), freeConnections(NULL) { @@ -335,105 +349,108 @@ Network::Network() void Network::AppendTransaction(NetworkTransaction* volatile* list, NetworkTransaction *r) { - ++inLwip; r->next = NULL; while (*list != NULL) { list = &((*list)->next); } *list = r; - --inLwip; } void Network::PrependTransaction(NetworkTransaction* volatile* list, NetworkTransaction *r) { - ++inLwip; r->next = *list; *list = r; - --inLwip; } void Network::Init() { if (!isEnabled) { - reprap.GetPlatform()->Message(HOST_MESSAGE, "Attempting to start the network when it is disabled.\n"); + platform->Message(HOST_MESSAGE, "Attempting to start the network when it is disabled.\n"); return; } - RepRapNetworkSetMACAddress(reprap.GetPlatform()->MACAddress()); + RepRapNetworkSetMACAddress(platform->MACAddress()); init_ethernet(); + longWait = platform->Time(); state = NetworkInitializing; } void Network::Spin() { + // Basically we can't do anything if we can't interact with LWIP + + if (!LockLWIP()) + { + platform->ClassReport(longWait); + return; + } + if (state == NetworkActive) { // See if we can read any packets + if (readingData) { readingData = false; - ++inLwip; do { // read all queued packets from the RX buffer } while (ethernet_read()); - --inLwip; ethernet_set_rx_callback(&emac_read_packet); } // See if we can send anything - ++inLwip; + NetworkTransaction *r = writingTransactions; if (r != NULL && r->Send()) { - ConnectionState *cs = r->cs; + // We're done, free up this transaction - writingTransactions = r->next; + ConnectionState *cs = r->cs; NetworkTransaction *rn = r->nextWrite; - r->nextWrite = NULL; + writingTransactions = r->next; AppendTransaction(&freeTransactions, r); - if (rn != NULL) + // If there is more data to write on this connection, do it next time + + if (cs != NULL) { - if (cs != NULL) - { - cs->sendingTransaction = (rn->cs == cs) ? rn : NULL; - } - PrependTransaction(&writingTransactions, rn); + cs->sendingTransaction = rn; } - else if (cs != NULL) + if (rn != NULL) { - cs->sendingTransaction = NULL; + PrependTransaction(&writingTransactions, rn); } } - --inLwip; } else if (state == NetworkInitializing && establish_ethernet_link()) { - start_ethernet(reprap.GetPlatform()->IPAddress(), reprap.GetPlatform()->NetMask(), reprap.GetPlatform()->GateWay()); + start_ethernet(platform->IPAddress(), platform->NetMask(), platform->GateWay()); httpd_init(); ftpd_init(); telnetd_init(); ethernet_set_rx_callback(&emac_read_packet); state = NetworkActive; } + + UnlockLWIP(); + platform->ClassReport(longWait); } void Network::Interrupt() { - if (!inLwip && state != NetworkInactive) + if (state != NetworkInactive && LockLWIP()) { - ++inLwip; ethernet_timers_update(); - --inLwip; + UnlockLWIP(); } } void Network::Diagnostics() { - reprap.GetPlatform()->AppendMessage(BOTH_MESSAGE, "Network diagnostics:\n"); + platform->AppendMessage(BOTH_MESSAGE, "Network Diagnostics:\n"); uint8_t numFreeConnections = 0; ConnectionState *freeConn = freeConnections; @@ -442,7 +459,7 @@ void Network::Diagnostics() numFreeConnections++; freeConn = freeConn->next; } - reprap.GetPlatform()->AppendMessage(BOTH_MESSAGE, "Free connections: %d of %d\n", numFreeConnections, numConnections); + platform->AppendMessage(BOTH_MESSAGE, "Free connections: %d of %d\n", numFreeConnections, numConnections); uint8_t numFreeTransactions = 0; NetworkTransaction *freeTrans = freeTransactions; @@ -451,7 +468,7 @@ void Network::Diagnostics() numFreeTransactions++; freeTrans = freeTrans->next; } - reprap.GetPlatform()->AppendMessage(BOTH_MESSAGE, "Free transactions: %d of %d\n", numFreeTransactions, networkTransactionCount); + platform->AppendMessage(BOTH_MESSAGE, "Free transactions: %d of %d\n", numFreeTransactions, networkTransactionCount); uint16_t numFreeSendBuffs = 0; SendBuffer *freeSendBuff = freeSendBuffers; @@ -460,17 +477,16 @@ void Network::Diagnostics() numFreeSendBuffs++; freeSendBuff = freeSendBuff->next; } - reprap.GetPlatform()->AppendMessage(BOTH_MESSAGE, "Free send buffers: %d of %d\n", numFreeSendBuffs, tcpOutputBufferCount); -} + platform->AppendMessage(BOTH_MESSAGE, "Free send buffers: %d of %d\n", numFreeSendBuffs, tcpOutputBufferCount); -bool Network::InLwip() const -{ - return (inLwip); -} -void Network::ReadPacket() -{ - readingData = true; +#if LWIP_STATS + // Normally we should NOT try to display LWIP stats here, because it uses debugPrintf(), which will hang the system is no USB cable is connected. + if (reprap.Debug(moduleNetwork)) + { + stats_display(); + } +#endif } void Network::Enable() @@ -505,7 +521,7 @@ bool Network::AllocateSendBuffer(SendBuffer *&buffer) buffer = freeSendBuffers; if (buffer == NULL) { - RepRapNetworkMessage("Network: Could not allocate send buffer!\n"); + platform->Message(HOST_MESSAGE, "Network: Could not allocate send buffer!\n"); return false; } freeSendBuffers = buffer->next; @@ -563,20 +579,17 @@ void Network::SentPacketAcknowledged(ConnectionState *cs, unsigned int len) // This is called when a connection is being established and returns an initialised ConnectionState instance. ConnectionState *Network::ConnectionAccepted(tcp_pcb *pcb) { - ++inLwip; ConnectionState *cs = freeConnections; if (cs == NULL) { - --inLwip; - reprap.GetPlatform()->Message(HOST_MESSAGE, "Network::ConnectionAccepted() - no free ConnectionStates!\n"); + platform->Message(HOST_MESSAGE, "Network::ConnectionAccepted() - no free ConnectionStates!\n"); return NULL; } NetworkTransaction* r = freeTransactions; if (r == NULL) { - --inLwip; - reprap.GetPlatform()->Message(HOST_MESSAGE, "Network::ConnectionAccepted() - no free transactions!\n"); + platform->Message(HOST_MESSAGE, "Network::ConnectionAccepted() - no free transactions!\n"); return NULL; } @@ -585,7 +598,6 @@ ConnectionState *Network::ConnectionAccepted(tcp_pcb *pcb) r->Set(NULL, cs, connected); freeTransactions = r->next; - --inLwip; AppendTransaction(&readyTransactions, r); return cs; @@ -621,14 +633,13 @@ void Network::ConnectionClosed(ConnectionState* cs, bool closeConnection) tcp_recv(pcb, NULL); tcp_poll(pcb, NULL, 4); tcp_close(pcb); + cs->pcb = NULL; } } // cs points to a connection state block that the caller is about to release, so we need to stop referring to it. // There may be one NetworkTransaction in the writing or closing list referring to it, and possibly more than one in the ready list. - //RepRapNetworkMessage("Network: ConnectionError\n"); - // See if it's a ready transaction for (NetworkTransaction* r = readyTransactions; r != NULL; r = r->next) { if (r->cs == cs) @@ -647,39 +658,51 @@ void Network::ConnectionClosed(ConnectionState* cs, bool closeConnection) freeConnections = cs; } -// May be called from ISR void Network::ConnectionClosedGracefully(ConnectionState *cs) { - ++inLwip; NetworkTransaction* r = freeTransactions; if (r == NULL) { - --inLwip; - reprap.GetPlatform()->Message(HOST_MESSAGE, "Network::ConnectionClosedGracefully() - no free transactions!\n"); + platform->Message(HOST_MESSAGE, "Network::ConnectionClosedGracefully() - no free transactions!\n"); return; } freeTransactions = r->next; r->Set(NULL, cs, disconnected); - --inLwip; AppendTransaction(&readyTransactions, r); } -// May be called from ISR +bool Network::Lock() +{ + return LockLWIP(); +} + +void Network::Unlock() +{ + UnlockLWIP(); +} + +bool Network::InLwip() const +{ + return lwipLocked; +} + +void Network::ReadPacket() +{ + readingData = true; +} + void Network::ReceiveInput(pbuf *pb, ConnectionState* cs) { - ++inLwip; NetworkTransaction* r = freeTransactions; if (r == NULL) { - --inLwip; - reprap.GetPlatform()->Message(HOST_MESSAGE, "Network::ReceiveInput() - no free transactions!\n"); + platform->Message(HOST_MESSAGE, "Network::ReceiveInput() - no free transactions!\n"); return; } freeTransactions = r->next; r->Set(pb, cs, dataReceiving); - --inLwip; AppendTransaction(&readyTransactions, r); // debugPrintf("Network - input received\n"); @@ -692,11 +715,36 @@ void Network::ReceiveInput(pbuf *pb, ConnectionState* cs) // will return the same one. NetworkTransaction *Network::GetTransaction(const ConnectionState *cs) { - ++inLwip; + // See if there is any transaction at all NetworkTransaction *rs = readyTransactions; - if (rs == NULL || cs == NULL || rs->cs == cs) + if (rs == NULL) + { + return NULL; + } + + // If we're waiting for a new connection on a data port, see if there is a matching transaction available + if (cs == NULL && rs->waitingForDataConnection) + { + const uint16_t localPort = rs->GetLocalPort(); + for (NetworkTransaction *rsNext = rs->next; rsNext != NULL; rsNext = rs->next) + { + if (rsNext->status == connected && rsNext->GetLocalPort() > 1023) + { + rs->next = rsNext->next; // remove rsNext from the list + rsNext->next = readyTransactions; + readyTransactions = rsNext; + return rsNext; + } + + rs = rsNext; + } + + return readyTransactions; // nothing found, process this transaction once again + } + + // See if the first one is the transaction we're looking for + if (cs == NULL || rs->cs == cs) { - --inLwip; return rs; } @@ -708,14 +756,12 @@ NetworkTransaction *Network::GetTransaction(const ConnectionState *cs) rs->next = rsNext->next; // remove rsNext from the list rsNext->next = readyTransactions; readyTransactions = rsNext; - --inLwip; return rsNext; } rs = rsNext; } - --inLwip; return NULL; } @@ -723,25 +769,22 @@ NetworkTransaction *Network::GetTransaction(const ConnectionState *cs) // The file may be too large for our buffer, so we may have to send it in multiple transactions. void Network::SendAndClose(FileStore *f, bool keepConnectionOpen) { - ++inLwip; NetworkTransaction *r = readyTransactions; if (r == NULL) { - --inLwip; + return; } - else if (r->status == dataSending) + + if (r->status == dataSending) { // This transaction is already in use for sending (e.g. a Telnet request), // so all we have to do is to remove it from readyTransactions. readyTransactions = r->next; - --inLwip; } else { readyTransactions = r->next; - --inLwip; - r->FreePbuf(); if (r->LostConnection()) { if (f != NULL) @@ -757,8 +800,8 @@ void Network::SendAndClose(FileStore *f, bool keepConnectionOpen) } else { + r->FreePbuf(); r->cs->persistConnection = keepConnectionOpen; - r->nextWrite = NULL; r->fileBeingSent = f; r->status = dataSending; if (f != NULL && r->sendBuffer == NULL) @@ -776,8 +819,8 @@ void Network::SendAndClose(FileStore *f, bool keepConnectionOpen) } } - NetworkTransaction *sendingTransaction = r->cs->sendingTransaction; - if (sendingTransaction == NULL) + NetworkTransaction *mySendingTransaction = r->cs->sendingTransaction; + if (mySendingTransaction == NULL) { r->cs->sendingTransaction = r; AppendTransaction(&writingTransactions, r); @@ -787,24 +830,27 @@ void Network::SendAndClose(FileStore *f, bool keepConnectionOpen) } else { - while (sendingTransaction->nextWrite != NULL) + while (mySendingTransaction->nextWrite != NULL) { - sendingTransaction = sendingTransaction->nextWrite; + mySendingTransaction = mySendingTransaction->nextWrite; } - sendingTransaction->nextWrite = r; + mySendingTransaction->nextWrite = r; // debugPrintf("Transaction appended to sending RS\n"); } } } } -// We have no data to read nor to write and we want to keep the current connection alive if possible. +// We have no data to write and we want to keep the current connection alive if possible. // That way we can speed up freeing the current NetworkTransaction. void Network::CloseTransaction() { // Free the current NetworkTransaction's data (if any) - ++inLwip; NetworkTransaction *r = readyTransactions; + if (r == NULL) + { + return; + } r->FreePbuf(); // Terminate this connection if this NetworkTransaction indicates a graceful disconnect @@ -817,7 +863,6 @@ void Network::CloseTransaction() // Remove the current item from readyTransactions readyTransactions = r->next; - --inLwip; // Append it to freeTransactions again unless it's already on another list if (status != dataSending) @@ -827,112 +872,83 @@ void Network::CloseTransaction() } -// The current NetworkTransaction must be processed again, e.g. because we're still waiting for another -// data connection. -void Network::RepeatTransaction() +// The current NetworkTransaction must be processed again, +// e.g. because we're still waiting for another data connection. +void Network::WaitForDataConection() { - ++inLwip; NetworkTransaction *r = readyTransactions; + r->waitingForDataConnection = true; r->inputPointer = 0; // behave as if this request hasn't been processed yet - if (r->next != NULL) - { - readyTransactions = r->next; - --inLwip; - - AppendTransaction(&readyTransactions, r); - } - else - { - --inLwip; - } } void Network::OpenDataPort(uint16_t port) { - ++inLwip; + closingDataPort = false; tcp_pcb* pcb = tcp_new(); tcp_bind(pcb, IP_ADDR_ANY, port); ftp_pasv_pcb = tcp_listen(pcb); tcp_accept(ftp_pasv_pcb, conn_accept); - --inLwip; } -// Close the data port and return true on success -bool Network::CloseDataPort() +uint16_t Network::GetDataPort() const +{ + return (closingDataPort || (ftp_pasv_pcb == NULL) ? 0 : ftp_pasv_pcb->local_port); +} + +// Close FTP data port and purge associated PCB +void Network::CloseDataPort() { // See if it's already being closed if (closingDataPort) { - return false; + return; } + closingDataPort = true; - // Close the open data connection if there is any + // Close remote connection of our data port or do it as soon as the current transaction has finished if (dataCs != NULL && dataCs->pcb != NULL) { - NetworkTransaction *sendingTransaction = dataCs->sendingTransaction; - if (sendingTransaction != NULL) - { - // we can't close the connection as long as we're sending - closingDataPort = true; - sendingTransaction->Close(); - return false; - } - else + NetworkTransaction *mySendingTransaction = dataCs->sendingTransaction; + if (mySendingTransaction != NULL) { - // close the data connection -// debugPrintf("CloseDataPort is closing connection dataCS=%08x\n", (unsigned int)loc_cs); - ++inLwip; - ConnectionClosed(dataCs, true); - --inLwip; + mySendingTransaction->Close(); + return; } } - // close listening data port + // We can close it now, so do it here if (ftp_pasv_pcb != NULL) { - ++inLwip; tcp_accept(ftp_pasv_pcb, NULL); tcp_close(ftp_pasv_pcb); ftp_pasv_pcb = NULL; - --inLwip; } - - return true; + closingDataPort = false; } // These methods keep track of our connections in case we need to send to one of them void Network::SaveDataConnection() { - ++inLwip; dataCs = readyTransactions->cs; - --inLwip; } void Network::SaveFTPConnection() { - ++inLwip; ftpCs = readyTransactions->cs; - --inLwip; } void Network::SaveTelnetConnection() { - ++inLwip; telnetCs = readyTransactions->cs; - --inLwip; } // Check if there are enough resources left to allocate another NetworkTransaction for sending bool Network::CanAcquireTransaction() { - ++inLwip; if (freeTransactions == NULL) { - --inLwip; return false; } - --inLwip; - return (freeSendBuffers != NULL); } @@ -951,22 +967,28 @@ bool Network::AcquireTelnetTransaction() return AcquireTransaction(telnetCs); } -// Retrieves the NetworkTransaction of a sending connection to which dataLength bytes can be appended at -// the present time or returns a released NetworkTransaction, which can easily be sent via SendAndClose. +// Retrieves the NetworkTransaction of a sending connection to which data can be appended to, +// or prepares a released NetworkTransaction, which can easily be sent via SendAndClose. bool Network::AcquireTransaction(ConnectionState *cs) { // Make sure we have a valid connection if (cs == NULL) { - reprap.GetPlatform()->Message(BOTH_ERROR_MESSAGE, "Attempting to allocate transaction for no connection!\n"); return false; } + // If our current transaction already belongs to cs and can be used, don't look for another one + NetworkTransaction *currentTransaction = readyTransactions; + if (currentTransaction != NULL && currentTransaction->GetConnection() == cs && currentTransaction->fileBeingSent == NULL) + { + return true; + } + // See if we're already writing on this connection NetworkTransaction *lastTransaction = cs->sendingTransaction; if (lastTransaction != NULL) { - while (lastTransaction->next != NULL) + while (lastTransaction->nextWrite != NULL) { lastTransaction = lastTransaction->nextWrite; } @@ -981,16 +1003,13 @@ bool Network::AcquireTransaction(ConnectionState *cs) // We cannot use it, so try to allocate a free one else { - ++inLwip; transactionToUse = freeTransactions; if (transactionToUse == NULL) { - --inLwip; - reprap.GetPlatform()->Message(HOST_MESSAGE, "Could not acquire free transaction!\n"); + platform->Message(HOST_MESSAGE, "Network: Could not acquire free transaction!\n"); return false; } freeTransactions = transactionToUse->next; - --inLwip; transactionToUse->Set(NULL, cs, dataReceiving); // set it to dataReceiving as we expect a response } @@ -1027,6 +1046,13 @@ void NetworkTransaction::Set(pbuf *p, ConnectionState *c, TransactionStatus s) closeRequested = false; nextWrite = NULL; lastWriteTime = NAN; + waitingForDataConnection = false; +} + +// How many incoming bytes do we have to process? +uint16_t NetworkTransaction::DataLength() const +{ + return (pb == NULL) ? 0 : pb->tot_len; } // Webserver calls this to read bytes that have come in from the network. @@ -1231,8 +1257,9 @@ void NetworkTransaction::Printf(const char* fmt, ...) // Send exactly one TCP window of data or return true if we can free up this object bool NetworkTransaction::Send() { - // We can't send any data if the connection has been lost - if (LostConnection()) + // Free up this transaction if we either lost our connection or are supposed to close it now + + if (LostConnection() || closeRequested) { if (fileBeingSent != NULL) { @@ -1246,27 +1273,12 @@ bool NetworkTransaction::Send() sendBuffer = net->ReleaseSendBuffer(sendBuffer); } - sendingTransaction = NULL; - sentDataOutstanding = 0; - - return true; - } - - // We've finished with this RS and want to close the connection, so do it here - if (closeRequested) - { - // Close the file if it is still open - if (fileBeingSent != NULL) + if (!LostConnection()) { - fileBeingSent->Close(); - fileBeingSent = NULL; +// debugPrintf("NetworkTransaction is closing connection cs=%08x\n", (unsigned int)cs); + reprap.GetNetwork()->ConnectionClosed(cs, true); } - // Close the connection PCB -// debugPrintf("NetworkTransaction is closing connection cs=%08x\n", (unsigned int)cs); - reprap.GetNetwork()->ConnectionClosed(cs, true); - - // Close the main connection if possible if (closingDataPort) { if (ftp_pasv_pcb != NULL) @@ -1278,9 +1290,15 @@ bool NetworkTransaction::Send() closingDataPort = false; } + + sendingTransaction = NULL; + sentDataOutstanding = 0; + + return true; } // We're still waiting for data to be ACK'ed, so check timeouts here + if (sentDataOutstanding) { if (!isnan(lastWriteTime)) @@ -1289,8 +1307,8 @@ bool NetworkTransaction::Send() if (timeNow - lastWriteTime > writeTimeout) { reprap.GetPlatform()->Message(HOST_MESSAGE, "Network: Timing out connection cs=%08x\n", (unsigned int)cs); - Close(); - lastWriteTime = NAN; + tcp_abort(cs->pcb); + cs->pcb = NULL; } return false; } @@ -1301,6 +1319,7 @@ bool NetworkTransaction::Send() } // See if we can fill up the TCP window with some data chunks from our SendBuffer instances + uint16_t bytesBeingSent = 0, bytesLeftToSend = TCP_WND; while (sendBuffer != NULL && bytesLeftToSend >= sendBuffer->bytesToWrite) { @@ -1312,21 +1331,9 @@ bool NetworkTransaction::Send() } // We also intend to send a file, so check if we can fill up the TCP window + if (sendBuffer == NULL) { - /*char c; - while (bytesBeingSent != TCP_WND) - { - if (!fileBeingSent->Read(c)) - { - fileBeingSent->Close(); - fileBeingSent = NULL; - break; - } - sendingWindow[bytesBeingSent] = c; - bytesBeingSent++; - }*/ - int bytesRead; size_t bytesToRead; while (bytesLeftToSend && fileBeingSent != NULL) @@ -1367,10 +1374,10 @@ bool NetworkTransaction::Send() tcp_sent(cs->pcb, conn_sent); if (tcp_write(cs->pcb, sendingWindow, bytesBeingSent, 0 /*TCP_WRITE_FLAG_COPY*/ ) != ERR_OK) // Final arg - 1 means make a copy { - RepRapNetworkMessage("tcp_write encountered an error, this should never happen!\n"); - cs->pcb = NULL; + reprap.GetPlatform()->Message(HOST_MESSAGE, "Network: tcp_write encountered an error, this should never happen!\n"); tcp_abort(cs->pcb); + cs->pcb = NULL; } else { @@ -1396,6 +1403,11 @@ void NetworkTransaction::SetConnectionLost() } } +uint32_t NetworkTransaction::GetRemoteIP() const +{ + return (cs != NULL) ? cs->pcb->remote_ip.addr : 0; +} + uint16_t NetworkTransaction::GetLocalPort() const { return (cs != NULL) ? cs->pcb->local_port : 0; @@ -1403,12 +1415,10 @@ uint16_t NetworkTransaction::GetLocalPort() const void NetworkTransaction::Close() { - ++inLwip; tcp_pcb *pcb = cs->pcb; tcp_poll(pcb, NULL, 4); tcp_recv(pcb, NULL); closeRequested = true; - --inLwip; } void NetworkTransaction::FreePbuf() @@ -1416,10 +1426,8 @@ void NetworkTransaction::FreePbuf() // Tell LWIP that we have processed data if (cs != NULL && bufferLength > 0 && cs->pcb != NULL) { - ++inLwip; tcp_recved(cs->pcb, bufferLength); bufferLength = 0; - --inLwip; } // Free pbuf (pbufs are thread-safe) @@ -11,7 +11,6 @@ Separated out from Platform.h by dc42 and extended by zpl #include <cctype> #include <cstring> -#include <malloc.h> #include <cstdlib> #include <climits> @@ -76,6 +75,7 @@ public: NetworkTransaction(NetworkTransaction* n) : next(n) { } void Set(pbuf *p, ConnectionState* c, TransactionStatus s); + uint16_t DataLength() const; bool Read(char& b); bool ReadBuffer(char *&buffer, unsigned int &len); void Write(char b); @@ -86,9 +86,9 @@ public: bool Send(); void SetConnectionLost(); - bool LostConnection() const { return cs == NULL; } - bool IsReady() const { return cs != NULL && cs->sendingTransaction == NULL; } + bool LostConnection() const { return cs == NULL || cs->pcb == NULL; } ConnectionState *GetConnection() const { return cs; } + uint32_t GetRemoteIP() const; uint16_t GetLocalPort() const; TransactionStatus GetStatus() const { return status; } @@ -109,22 +109,23 @@ private: TransactionStatus status; float lastWriteTime; bool closeRequested; + bool waitingForDataConnection; }; // This class holds data left to be sent to TCP clients. class SendBuffer { -public: - friend class Network; - friend class NetworkTransaction; + public: + friend class Network; + friend class NetworkTransaction; - SendBuffer(SendBuffer *n) : next(n) { }; + SendBuffer(SendBuffer *n) : next(n) { }; -private: - SendBuffer *next; + private: + SendBuffer *next; - uint16_t bytesToWrite; - char tcpOutputBuffer[tcpOutputBufferSize]; + uint16_t bytesToWrite; + char tcpOutputBuffer[tcpOutputBufferSize]; }; @@ -134,6 +135,7 @@ class Network public: friend class NetworkTransaction; + void ReadPacket(); void ReceiveInput(pbuf *pb, ConnectionState *cs); void SentPacketAcknowledged(ConnectionState *cs, unsigned int len); ConnectionState *ConnectionAccepted(tcp_pcb *pcb); @@ -143,10 +145,11 @@ public: NetworkTransaction *GetTransaction(const ConnectionState *cs = NULL); void SendAndClose(FileStore *f, bool keepConnectionOpen = false); void CloseTransaction(); - void RepeatTransaction(); + void WaitForDataConection(); void OpenDataPort(uint16_t port); - bool CloseDataPort(); + uint16_t GetDataPort() const; + void CloseDataPort(); void SaveDataConnection(); void SaveFTPConnection(); @@ -157,20 +160,25 @@ public: bool AcquireDataTransaction(); bool AcquireTelnetTransaction(); - Network(); + Network(Platform* p); void Init(); void Spin(); void Interrupt(); void Diagnostics(); + bool Lock(); + void Unlock(); bool InLwip() const; - void ReadPacket(); void Enable(); void Disable(); bool IsEnabled() const; private: + + Platform* platform; + float longWait; + void AppendTransaction(NetworkTransaction* volatile * list, NetworkTransaction *r); void PrependTransaction(NetworkTransaction* volatile * list, NetworkTransaction *r); bool AcquireTransaction(ConnectionState *cs); diff --git a/Platform.cpp b/Platform.cpp index abe5932b..14ff79dd 100644 --- a/Platform.cpp +++ b/Platform.cpp @@ -138,17 +138,17 @@ void Platform::Init() SerialUSB.begin(baudRates[0]); Serial.begin(baudRates[1]); // this can't be done in the constructor because the Arduino port initialisation isn't complete at that point -# if __cplusplus >= 201103L - static_assert(sizeof(nvData) <= FLASH_DATA_LENGTH, "NVData too large"); -# else - // We are relying on the compiler optimising this out if the condition is false +#if __cplusplus >= 201103L + static_assert(sizeof(FlashData) + sizeof(SoftwareResetData) <= FLASH_DATA_LENGTH, "NVData too large"); +#else + // We are relying on the compiler optimizing this out if the condition is false // Watch out for the build warning "undefined reference to 'BadStaticAssert()' if this fails. - if (!(sizeof(nvData) <= FLASH_DATA_LENGTH)) + if (!(sizeof(FlashData) + sizeof(SoftwareResetData) <= FLASH_DATA_LENGTH)) { extern void BadStaticAssert(); BadStaticAssert(); } -# endif +#endif ResetNvData(); @@ -728,13 +728,12 @@ void Platform::Spin() line->Spin(); aux->Spin(); - ClassReport("Platform", longWait, modulePlatform); - + ClassReport(longWait); } void Platform::SoftwareReset(uint16_t reason) { - if (reason != 0) + if (reason != SoftwareResetReason::user) { if (line->inWrite) { @@ -749,12 +748,24 @@ void Platform::SoftwareReset(uint16_t reason) reason |= SoftwareResetReason::inAuxOutput; // if we are resetting because we are stuck in a Spin function, record whether we are trying to send to aux } } + reason |= reprap.GetSpinningModule(); - // Write the reason for the software reset to flash + // Record the reason for the software reset SoftwareResetData temp; temp.magic = SoftwareResetData::magicValue; temp.resetReason = reason; GetStackUsage(NULL, NULL, &temp.neverUsedRam); + if (reason != SoftwareResetReason::user) + { + strncpy(temp.lastMessage, messageString.Pointer(), sizeof(temp.lastMessage) - 1); + temp.lastMessage[sizeof(temp.lastMessage) - 1] = 0; + } + else + { + temp.lastMessage[0] = 0; + } + + // Save diagnostics data to Flash and reset the software DueFlashStorage::write(SoftwareResetData::nvAddress, &temp, sizeof(SoftwareResetData)); rstc_start_software_reset(RSTC); @@ -983,7 +994,6 @@ void Platform::Tick() // All other messages generated by this and other diagnostics functions must call AppendMessage. void Platform::Diagnostics() { - ReadNvData(); // need to do this to get the software reset code Message(BOTH_MESSAGE, "Platform Diagnostics:\n"); // Print memory stats and error codes to USB and copy them to the current webserver reply @@ -1014,6 +1024,11 @@ void Platform::Diagnostics() if (temp.magic == SoftwareResetData::magicValue) { AppendMessage(BOTH_MESSAGE, "Last software reset code & available RAM: 0x%04x, %u\n", temp.resetReason, temp.neverUsedRam); + AppendMessage(BOTH_MESSAGE, "Spinning module during software reset: %s\n", moduleName[temp.resetReason & 0x0F]); + if (temp.lastMessage[0]) + { + AppendMessage(BOTH_MESSAGE, "Last message before reset: %s", temp.lastMessage); // usually ends with NL + } } } @@ -1044,14 +1059,6 @@ void Platform::Diagnostics() reprap.Timing(); -#if LWIP_STATS - // Normally we should NOT try to display LWIP stats here, because it uses debugPrintf(), which will hang the system is no USB cable is connected. - if (reprap.Debug(moduleNetwork)) - { - stats_display(); - } -#endif - #ifdef MOVE_DEBUG AppendMessage(BOTH_MESSAGE, "Interrupts scheduled %u, done %u, last %u, next %u sched at %u, now %u\n", numInterruptsScheduled, numInterruptsExecuted, lastInterruptTime, nextInterruptTime, nextInterruptScheduledAt, GetInterruptClocks()); @@ -1069,6 +1076,11 @@ void Platform::DiagnosticTest(int d) case DiagnosticTest::TestSpinLockup: debugCode = d; // tell the Spin function to loop break; + + case DiagnosticTest::TestSerialBlock: // write an arbitrary message via debugPrintf() + debugPrintf("Diagnostic Test\n"); + break; + default: break; } @@ -1090,16 +1102,16 @@ void Platform::GetStackUsage(size_t* currentStack, size_t* maxStack, size_t* nev if (neverUsed) { *neverUsed = stack_lwm - heapend; } } -void Platform::ClassReport(const char* className, float &lastTime, Module m) +void Platform::ClassReport(float &lastTime) { - if (reprap.Debug(m)) + const Module spinningModule = reprap.GetSpinningModule(); + if (reprap.Debug(spinningModule)) { - if (Time() - lastTime < LONG_TIME) + if (Time() - lastTime >= LONG_TIME) { - return; + lastTime = Time(); + Message(HOST_MESSAGE, "Class %s spinning.\n", moduleName[spinningModule]); } - lastTime = Time(); - Message(HOST_MESSAGE, "Class %s spinning.\n", className); } } @@ -1328,7 +1340,7 @@ FileStore* Platform::GetFileStore(const char* directory, const char* fileName, b if (!fileStructureInitialised) return NULL; - for (int i = 0; i < MAX_FILES; i++) + for (size_t i = 0; i < MAX_FILES; i++) { if (!files[i]->inUse) { @@ -1369,6 +1381,12 @@ void Platform::Message(char type, const char* message, va_list vargs) void Platform::Message(char type, const StringRef& message) { + if (message.Pointer() != messageString.Pointer()) + { + // We might need to save the last message before a software reset is triggered + messageString.copy(message.Pointer()); + } + switch(type) { case FLASH_LED: @@ -1396,12 +1414,12 @@ void Platform::Message(char type, const StringRef& message) case WEB_MESSAGE: // Message that is to be sent to the web - reprap.GetWebserver()->MessageStringToWebInterface(message.Pointer(), false); + reprap.GetWebserver()->ResponseToWebInterface(message.Pointer(), false); break; case WEB_ERROR_MESSAGE: // Message that is to be sent to the web - flags an error - reprap.GetWebserver()->MessageStringToWebInterface(message.Pointer(), true); + reprap.GetWebserver()->ResponseToWebInterface(message.Pointer(), true); break; case BOTH_MESSAGE: @@ -1414,7 +1432,7 @@ void Platform::Message(char type, const StringRef& message) } } line->Write(message.Pointer()); - reprap.GetWebserver()->MessageStringToWebInterface(message.Pointer(), false); + reprap.GetWebserver()->ResponseToWebInterface(message.Pointer(), false); break; case BOTH_ERROR_MESSAGE: @@ -1430,7 +1448,7 @@ void Platform::Message(char type, const StringRef& message) } } line->Write(message.Pointer()); - reprap.GetWebserver()->MessageStringToWebInterface(message.Pointer(), true); + reprap.GetWebserver()->ResponseToWebInterface(message.Pointer(), true); break; } } @@ -1446,6 +1464,12 @@ void Platform::AppendMessage(char type, const char* message, ...) void Platform::AppendMessage(char type, const StringRef& message) { + if (message.Pointer() != messageString.Pointer()) + { + // We might need to save the last message before a software reset is triggered + messageString.cat(message.Pointer()); + } + switch(type) { case FLASH_LED: @@ -1474,12 +1498,9 @@ void Platform::AppendMessage(char type, const StringRef& message) case WEB_MESSAGE: // Message that is to be sent to the web - reprap.GetWebserver()->AppendReplyToWebInterface(message.Pointer(), false); - break; - case WEB_ERROR_MESSAGE: // Message that is to be sent to the web - flags an error - reprap.GetWebserver()->AppendReplyToWebInterface(message.Pointer(), true); + reprap.GetWebserver()->AppendResponseToWebInterface(message.Pointer()); break; case BOTH_MESSAGE: @@ -1492,7 +1513,7 @@ void Platform::AppendMessage(char type, const StringRef& message) } } line->Write(message.Pointer()); - reprap.GetWebserver()->AppendReplyToWebInterface(message.Pointer(), false); + reprap.GetWebserver()->AppendResponseToWebInterface(message.Pointer()); break; case BOTH_ERROR_MESSAGE: @@ -1508,11 +1529,15 @@ void Platform::AppendMessage(char type, const StringRef& message) } } line->Write(message.Pointer()); - reprap.GetWebserver()->AppendReplyToWebInterface(message.Pointer(), true); + reprap.GetWebserver()->AppendResponseToWebInterface(message.Pointer()); break; } } +bool Platform::AtxPower() const +{ + return (digitalReadNonDue(atxPowerPin) == HIGH); +} void Platform::SetAtxPower(bool on) { @@ -1532,7 +1557,7 @@ float Platform::ActualInstantDv(size_t drive) const { float idv = instantDvs[drive]; float eComp = elasticComp[drive]; - // If we are4 using elastic compensation then we need to limit the instantDv to avoid velocity mismatches + // If we are using elastic compensation then we need to limit the instantDv to avoid velocity mismatches return (eComp <= 0.0) ? idv : min<float>(idv, 1.0/(eComp * driveStepsPerUnit[drive])); } @@ -1849,7 +1874,6 @@ void FileStore::Init() // Open a local file (for example on an SD card). // This is protected - only Platform can access it. - bool FileStore::Open(const char* directory, const char* fileName, bool write) { const char* location = (directory != NULL) @@ -1857,12 +1881,16 @@ bool FileStore::Open(const char* directory, const char* fileName, bool write) : fileName; writing = write; lastBufferEntry = FILE_BUF_LEN - 1; - bytesRead = 0; FRESULT openReturn = f_open(&file, location, (writing) ? FA_CREATE_ALWAYS | FA_WRITE : FA_OPEN_EXISTING | FA_READ); if (openReturn != FR_OK) { - platform->Message(BOTH_ERROR_MESSAGE, "Can't open %s to %s, error code %d\n", location, (writing) ? "write" : "read", openReturn); + // We no longer report an error if opening a file in read mode fails unless debugging is enabled, because sometimes that is quite normal. + // It is up to the caller to report an error if necessary. + if (reprap.Debug(modulePlatform)) + { + platform->Message(BOTH_ERROR_MESSAGE, "Can't open %s to %s, error code %d\n", location, (writing) ? "write" : "read", openReturn); + } return false; } @@ -1906,7 +1934,7 @@ bool FileStore::Close() return ok && fr == FR_OK; } -bool FileStore::Seek(unsigned long pos) +bool FileStore::Seek(FilePosition pos) { if (!inUse) { @@ -1916,10 +1944,39 @@ bool FileStore::Seek(unsigned long pos) if (writing) { WriteBuffer(); + FRESULT fr = f_lseek(&file, pos); + if (fr == FR_OK) + { + bufferPointer = 0; + lastBufferEntry = 0; + return true; + } } - FRESULT fr = f_lseek(&file, pos); - bufferPointer = (writing) ? 0 : FILE_BUF_LEN; - return fr == FR_OK; + else + { + // Keep file reads aligned on a 256-byte boundary + FRESULT fr = f_lseek(&file, pos & ~(FilePosition)(FILE_BUF_LEN - 1)); + if (fr == FR_OK) + { + bool ok = ReadBuffer(); + if (ok) + { + bufferPointer = pos & (FilePosition)(FILE_BUF_LEN - 1); + return true; + } + } + } + return false; +} + +FilePosition FileStore::GetPosition() const +{ + FilePosition pos = file.fptr; + if (!writing && bufferPointer < lastBufferEntry) + { + pos -= (lastBufferEntry - bufferPointer); + } + return pos; } bool FileStore::GoToEnd() @@ -1927,7 +1984,7 @@ bool FileStore::GoToEnd() return Seek(Length()); } -unsigned long FileStore::Length() const +FilePosition FileStore::Length() const { if (!inUse) { @@ -1939,13 +1996,13 @@ unsigned long FileStore::Length() const float FileStore::FractionRead() const { - unsigned long len = Length(); - if(len <= 0) + uint32_t len = Length(); + if (len == 0) { return 0.0; } - return (float)bytesRead / (float)len; + return (float)GetPosition() / (float)len; } int8_t FileStore::Status() @@ -2000,7 +2057,6 @@ bool FileStore::Read(char& b) b = (char) buf[bufferPointer]; bufferPointer++; - bytesRead++; return true; } @@ -2021,7 +2077,6 @@ int FileStore::Read(char* extBuf, unsigned int nBytes) platform->Message(BOTH_ERROR_MESSAGE, "Error reading file.\n"); return -1; } - bytesRead += bytes_read; return (int)bytes_read; } @@ -57,8 +57,6 @@ Licence: GPL // Some numbers... -#define STRING_LENGTH 1029 -#define SHORT_STRING_LENGTH 40 #define TIME_TO_REPRAP 1.0e6 // Convert seconds to the units used by the machine (usually microseconds) #define TIME_FROM_REPRAP 1.0e-6 // Convert the units used by the machine (usually microseconds) to seconds @@ -269,8 +267,8 @@ namespace DiagnosticTest enum { TestWatchdog = 1001, // test that we get a watchdog reset if the tick interrupt stops - TestSpinLockup = 1002 // test that we get a software reset if a Spin() function takes too long - + TestSpinLockup = 1002, // test that we get a software reset if a Spin() function takes too long + TestSerialBlock = 1003 // test what happens when we write a blocking message via debugPrintf() }; } @@ -359,7 +357,10 @@ private: // This class handles input from, and output to, files. -class FileStore //: public InputOutput +typedef uint32_t FilePosition; +const FilePosition noFilePosition = 0xFFFFFFFF; + +class FileStore { public: @@ -370,9 +371,10 @@ public: bool Write(const char *s, unsigned int len); // Write a block of len bytes bool Write(const char* s); // Write a string bool Close(); // Shut the file and tidy up - bool Seek(unsigned long pos); // Jump to pos in the file + bool Seek(FilePosition pos); // Jump to pos in the file + FilePosition GetPosition() const; // Return the current position in the file, assuming we are reading the file bool GoToEnd(); // Position the file at the end (so you can write on the end). - unsigned long Length() const; // File size in bytes + FilePosition Length() const; // File size in bytes float FractionRead() const; // How far in we are void Duplicate(); // Create a second reference to this file bool Flush(); // Write remaining buffer data @@ -390,8 +392,7 @@ private: bool inUse; byte buf[FILE_BUF_LEN]; - int bufferPointer; - unsigned long bytesRead; + unsigned int bufferPointer; bool ReadBuffer(); bool WriteBuffer(); @@ -564,9 +565,10 @@ public: void SetEmulating(Compatibility c); void Diagnostics(); void DiagnosticTest(int d); - void ClassReport(const char* className, float &lastTime, Module m); // Called on return to check everything's live. + void ClassReport(float &lastTime); // Called on return to check everything's live. void RecordError(ErrorCode ec) { errorCodeBits |= ec; } void SoftwareReset(uint16_t reason); + bool AtxPower() const; void SetAtxPower(bool on); // Timing @@ -718,11 +720,12 @@ private: uint16_t magic; uint16_t resetReason; // this records why we did a software reset, for diagnostic purposes size_t neverUsedRam; // the amount of never used RAM at the last abnormal software reset + char lastMessage[256]; // the last known message before a software reset occurred }; struct FlashData { - static const uint16_t magicValue = 0xA436; // value we use to recognise that just the reset flash data has been written + static const uint16_t magicValue = 0xA436; // value we use to recognise that the flash data has been written static const uint32_t nvAddress = SoftwareResetData::nvAddress + sizeof(struct SoftwareResetData); uint16_t magic; @@ -897,7 +900,12 @@ public: return f->Flush(); } - bool Seek(unsigned long position) + uint32_t GetPosition() const + { + return f->GetPosition(); + } + + bool Seek(uint32_t position) { return f->Seek(position); } @@ -907,7 +915,7 @@ public: return (f == NULL ? -1.0 : f->FractionRead()); } - unsigned long Length() + uint32_t Length() const { return f->Length(); } diff --git a/Release/RepRapFirmware-065k-dc42.bin b/Release/RepRapFirmware-065k-dc42.bin Binary files differdeleted file mode 100644 index 3f2f447e..00000000 --- a/Release/RepRapFirmware-065k-dc42.bin +++ /dev/null diff --git a/Release/RepRapFirmware-078v-dc42.bin b/Release/RepRapFirmware-078v-dc42.bin Binary files differdeleted file mode 100644 index 12006761..00000000 --- a/Release/RepRapFirmware-078v-dc42.bin +++ /dev/null diff --git a/Release/RepRapFirmware-078x-dc42.bin b/Release/RepRapFirmware-078x-dc42.bin Binary files differdeleted file mode 100644 index 7cd32f07..00000000 --- a/Release/RepRapFirmware-078x-dc42.bin +++ /dev/null diff --git a/Release/RepRapFirmware-078y-dc42.bin b/Release/RepRapFirmware-078y-dc42.bin Binary files differdeleted file mode 100644 index 51d3ba1e..00000000 --- a/Release/RepRapFirmware-078y-dc42.bin +++ /dev/null diff --git a/Release/RepRapFirmware-1.00a-dc42.bin b/Release/RepRapFirmware-1.00a-dc42.bin Binary files differdeleted file mode 100644 index b76529ed..00000000 --- a/Release/RepRapFirmware-1.00a-dc42.bin +++ /dev/null diff --git a/Release/RepRapFirmware-1.00c-57600.bin b/Release/RepRapFirmware-1.00c-57600.bin Binary files differdeleted file mode 100644 index 150a88f8..00000000 --- a/Release/RepRapFirmware-1.00c-57600.bin +++ /dev/null diff --git a/Release/RepRapFirmware-1.00h.bin b/Release/RepRapFirmware-1.00h.bin Binary files differnew file mode 100644 index 00000000..8eaebfbc --- /dev/null +++ b/Release/RepRapFirmware-1.00h.bin diff --git a/RepRapFirmware.cpp b/RepRapFirmware.cpp index 0e696976..dc63d704 100644 --- a/RepRapFirmware.cpp +++ b/RepRapFirmware.cpp @@ -157,17 +157,33 @@ Licence: GPL RepRap reprap; +const char *moduleName[] = +{ + "Platform", + "Network", + "Webserver", + "GCodes", + "Move", + "Heat", + "DDA", + "?","?","?","?","?","?","?","?", + "none" +}; + //************************************************************************************************* // RepRap member functions. // Do nothing more in the constructor; put what you want in RepRap:Init() -RepRap::RepRap() : active(false), debug(0), stopped(false), currentModule(noModule), ticksInSpinState(0), resetting(false), fileInfoDetected(false), printStartTime(0.0) +RepRap::RepRap() : active(false), debug(0), stopped(false), spinningModule(noModule), ticksInSpinState(0), + resetting(false), fileInfoDetected(false), printStartTime(0.0), gcodeReply(gcodeReplyBuffer, GCODE_REPLY_LENGTH), + currentLayer(0), firstLayerDuration(0.0), firstLayerHeight(0.0), firstLayerFilament(0.0), firstLayerProgress(0.0), + warmUpDuration(0.0), layerEstimatedTimeLeft(0.0), lastLayerTime(0.0), lastLayerFilament(0.0), numLayerSamples(0) { platform = new Platform(); - network = new Network(); - webserver = new Webserver(platform); + network = new Network(platform); + webserver = new Webserver(platform, network); gCodes = new GCodes(platform, webserver); move = new Move(platform, gCodes); heat = new Heat(platform, gCodes); @@ -179,6 +195,14 @@ void RepRap::Init() debug = 0; activeExtruders = 1; // we always report at least 1 extruder to the web interface activeHeaters = 2; // we always report the bed heater + 1 extruder heater to the web interface + SetPassword(DEFAULT_PASSWORD); + SetName(DEFAULT_NAME); + + beepFrequency = beepDuration = 0; + message[0] = 0; + + gcodeReply[0] = 0; + replySeq = 0; processingConfig = true; // All of the following init functions must execute reasonably quickly before the watchdog times us out @@ -216,7 +240,7 @@ void RepRap::Init() bool runningTheFile = false; bool initialisingInProgress = true; - while(initialisingInProgress) + while (initialisingInProgress) { Spin(); if(gCodes->PrintingAFile()) @@ -233,8 +257,15 @@ void RepRap::Init() } processingConfig = false; - platform->AppendMessage(HOST_MESSAGE, "\nStarting network...\n"); - network->Init(); // Need to do this here, as the configuration GCodes may set IP address etc. + if (network->IsEnabled()) + { + platform->AppendMessage(HOST_MESSAGE, "\nStarting network...\n"); + network->Init(); // Need to do this here, as the configuration GCodes may set IP address etc. + } + else + { + platform->AppendMessage(HOST_MESSAGE, "\nNetwork disabled.\n"); + } platform->AppendMessage(HOST_MESSAGE, "\n%s is up and running.\n", NAME); fastLoop = FLT_MAX; @@ -258,33 +289,36 @@ void RepRap::Spin() if(!active) return; - currentModule = modulePlatform; + spinningModule = modulePlatform; ticksInSpinState = 0; platform->Spin(); - currentModule = moduleNetwork; + spinningModule = moduleNetwork; ticksInSpinState = 0; network->Spin(); - currentModule = moduleWebserver; + spinningModule = moduleWebserver; ticksInSpinState = 0; webserver->Spin(); - currentModule = moduleGcodes; + spinningModule = moduleGcodes; ticksInSpinState = 0; gCodes->Spin(); - currentModule = moduleMove; + spinningModule = moduleMove; ticksInSpinState = 0; move->Spin(); - currentModule = moduleHeat; + spinningModule = moduleHeat; ticksInSpinState = 0; heat->Spin(); - currentModule = noModule; + spinningModule = noModule; ticksInSpinState = 0; + // Update the print stats + UpdatePrintProgress(); + // Keep track of the loop time double t = platform->Time(); @@ -356,6 +390,44 @@ void RepRap::EmergencyStop() } } +void RepRap::SetDebug(Module m, bool enable) +{ + if (enable) + { + debug |= (1 << m); + } + else + { + debug &= ~(1 << m); + } + PrintDebug(); +} + +void RepRap::SetDebug(bool enable) +{ + debug = (enable) ? 0xFFFF : 0; +} + +void RepRap::PrintDebug() +{ + if (debug != 0) + { + platform->Message(BOTH_MESSAGE, "Debugging enabled for modules:"); + for(uint8_t i=0; i<16;i++) + { + if (debug & (1 << i)) + { + platform->AppendMessage(BOTH_MESSAGE, " %s", moduleName[i]); + } + } + platform->AppendMessage(BOTH_MESSAGE, "\n"); + } + else + { + platform->Message(BOTH_MESSAGE, "Debugging disabled\n"); + } +} + /* * The first tool added becomes the one selected. This will not happen in future releases. */ @@ -409,7 +481,7 @@ void RepRap::PrintTool(int toolNumber, StringRef& reply) const return; } } - reply.copy("Attempt to print details of non-existent tool."); + reply.copy("Attempt to print details of non-existent tool.\n"); } void RepRap::StandbyTool(int toolNumber) @@ -440,12 +512,35 @@ Tool* RepRap::GetTool(int toolNumber) while(tool) { if(tool->Number() == toolNumber) + { return tool; + } tool = tool->Next(); } return NULL; // Not an error } +#if 0 // not used +Tool* RepRap::GetToolByDrive(int driveNumber) +{ + Tool* tool = toolList; + + while (tool) + { + for(uint8_t drive = 0; drive < tool->DriveCount(); drive++) + { + if (tool->Drive(drive) + AXES == driveNumber) + { + return tool; + } + } + + tool = tool->Next(); + } + return NULL; +} +#endif + void RepRap::SetToolVariables(int toolNumber, float* standbyTemperatures, float* activeTemperatures) { Tool* tool = toolList; @@ -487,28 +582,377 @@ void RepRap::Tick() } move->PrintCurrentDda(); - platform->SoftwareReset(SoftwareResetReason::stuckInSpin + (unsigned int)currentModule); + platform->SoftwareReset(SoftwareResetReason::stuckInSpin); } } } } +// Get the JSON status response for the web server (or later for the M105 command). +// Type 1 is the ordinary JSON status response. +// Type 2 is the same except that static parameters are also included. +// Type 3 is the same but instead of static parameters we report print estimation values. +void RepRap::GetStatusResponse(StringRef& response, uint8_t type, bool forWebserver) +{ + char ch; + + // Machine status + if (processingConfig) + { + // Reading the configuration file + ch = 'C'; + } + else if (IsStopped()) + { + // Halted + ch = 'H'; + } + else if (gCodes->IsPausing()) + { + // Pausing / Decelerating + ch = 'D'; + } + else if (gCodes->IsResuming()) + { + // Resuming + ch = 'R'; + } + else if (gCodes->IsPaused()) + { + // Paused / Stopped + ch = 'S'; + } + else if (gCodes->PrintingAFile()) + { + // Printing + ch = 'P'; + } + else if (gCodes->DoingFileMacro() || !move->NoLiveMovement()) + { + // Busy + ch = 'B'; + } + else + { + // Idle + ch = 'I'; + } + response.printf("{\"status\":\"%c\",\"coords\":{", ch); + + /* Coordinates */ + { + float liveCoordinates[DRIVES + 1]; + if (currentTool != NULL) + { + const float *offset = currentTool->GetOffset(); + for (size_t i = 0; i < AXES; ++i) + { + liveCoordinates[i] += offset[i]; + } + } + move->LiveCoordinates(liveCoordinates); + + // Homed axes + response.catf("\"axesHomed\":[%d,%d,%d]", + (gCodes->GetAxisIsHomed(0)) ? 1 : 0, + (gCodes->GetAxisIsHomed(1)) ? 1 : 0, + (gCodes->GetAxisIsHomed(2)) ? 1 : 0); + + // Actual and theoretical extruder positions since power up, last G92 or last M23 + response.catf(",\"extr\":"); // announce actual extruder positions + ch = '['; + for (uint8_t extruder = 0; extruder < GetExtrudersInUse(); extruder++) + { + response.catf("%c%.1f", ch, liveCoordinates[AXES + extruder]); + ch = ','; + } + + // XYZ positions + response.cat("],\"xyz\":"); + ch = '['; + for (uint8_t axis = 0; axis < AXES; axis++) + { + response.catf("%c%.2f", ch, liveCoordinates[axis]); + ch = ','; + } + } + + // Current tool number + int toolNumber = (currentTool == NULL) ? 0 : currentTool->Number(); + response.catf("]},\"currentTool\":%d", toolNumber); + + /* Output - only reported once */ + { + bool sendBeep = (beepDuration != 0 && beepFrequency != 0); + bool sendMessage = (message[0]) && ((gCodes->HaveAux() && !forWebserver) || (!gCodes->HaveAux() && forWebserver)); + if (sendBeep || sendMessage) + { + response.cat(",\"output\":{"); + + // Report beep values + if (sendBeep) + { + response.catf("\"beepDuration\":%d,\"beepFrequency\":%d", beepDuration, beepFrequency); + if (sendMessage) + { + response.cat(","); + } + + beepFrequency = beepDuration = 0; + } + + // Report message + if (sendMessage) + { + response.cat("\"message\":"); + EncodeString(response, message, 2, false); + + message[0] = 0; + } + response.cat("}"); + } + } + + /* Parameters */ + { + // ATX power + response.catf(",\"params\":{\"atxPower\":%d", platform->AtxPower() ? 1 : 0); + + // Cooling fan value + float fanValue = (gCodes->CoolingInverted() ? 1.0 - platform->GetFanValue() : platform->GetFanValue()); + response.catf(",\"fanPercent\":%.2f", fanValue * 100.0); + + // Speed and Extrusion factors + response.catf(",\"speedFactor\":%.2f,\"extrFactors\":", gCodes->GetSpeedFactor() * 100.0); + for (uint8_t extruder = 0; extruder < GetExtrudersInUse(); extruder++) + { + response.catf("%c%.2f", (extruder == 0) ? '[' : ',', gCodes->GetExtrusionFactors()[extruder] * 100.0); + } + response.cat("]}"); + } + + // G-code reply sequence for webserver + if (forWebserver) + { + response.catf(",\"seq\":%d", replySeq); + + // There currently appears to be no need for this one, so skip it + //response.catf(",\"buff\":%u", webserver->GetGcodeBufferSpace()); + } + + /* Sensors */ + { + response.cat(",\"sensors\":{"); + + // Probe + int v0 = platform->ZProbe(); + int v1, v2; + switch (platform->GetZProbeSecondaryValues(v1, v2)) + { + case 1: + response.catf("\"probeValue\":\%d,\"probeSecondary\":[%d]", v0, v1); + break; + case 2: + response.catf("\"probeValue\":\%d,\"probeSecondary\":[%d,%d]", v0, v1, v2); + break; + default: + response.catf("\"probeValue\":%d", v0); + break; + } + + // Fan RPM + response.catf(",\"fanRPM\":%d}", (unsigned int)platform->GetFanRPM()); + } + + /* Temperatures */ + { + response.cat(",\"temps\":{"); + + /* Bed */ +#if HOT_BED != -1 + { + response.catf("\"bed\":{\"current\":%.1f,\"active\":%.1f,\"state\":%d},", + heat->GetTemperature(HOT_BED), heat->GetActiveTemperature(HOT_BED), + heat->GetStatus(HOT_BED)); + } +#endif + + /* Heads */ + { + response.cat("\"heads\":{\"current\":"); + + // Current temperatures + ch = '['; + for (int8_t heater = E0_HEATER; heater < GetHeatersInUse(); heater++) + { + response.catf("%c%.1f", ch, heat->GetTemperature(heater)); + ch = ','; + } + + // Active temperatures + response.catf("],\"active\":"); + ch = '['; + for (int8_t heater = E0_HEATER; heater < GetHeatersInUse(); heater++) + { + response.catf("%c%.1f", ch, heat->GetActiveTemperature(heater)); + ch = ','; + } + + // Standby temperatures + response.catf("],\"standby\":"); + ch = '['; + for (int8_t heater = E0_HEATER; heater < GetHeatersInUse(); heater++) + { + response.catf("%c%.1f", ch, heat->GetStandbyTemperature(heater)); + ch = ','; + } + + // Heater statuses (0=off, 1=standby, 2=active, 3=fault) + response.cat("],\"state\":"); + ch = '['; + for (int8_t heater = E0_HEATER; heater < GetHeatersInUse(); heater++) + { + response.catf("%c%d", ch, (int)heat->GetStatus(heater)); + ch = ','; + } + } + response.cat("]}}"); + } + + // Time since last reset + response.catf(",\"time\":%.1f", platform->Time()); + + /* Extended Status Response */ + if (type == 2) + { + // Cold Extrude/Retract + response.catf(",\"coldExtrudeTemp\":%1.f", ColdExtrude() ? 0 : HOT_ENOUGH_TO_EXTRUDE); + response.catf(",\"coldRetractTemp\":%1.f", ColdExtrude() ? 0 : HOT_ENOUGH_TO_RETRACT); + + // Delta configuration + response.catf(",\"geometry\":\"%s\"", move->IsDeltaMode() ? "delta" : "cartesian"); + + // Machine name + response.cat(",\"name\":"); + EncodeString(response, myName, 2, false); + + /* Probe */ + { + const ZProbeParameters& probeParams = platform->GetZProbeParameters(); + + // Trigger threshold + response.catf(",\"probe\":{\"threshold\":%d", probeParams.adcValue); + + // Trigger height + response.catf(",\"height\":%.2f", probeParams.height); + + // Type + response.catf(",\"type\":%d}", platform->GetZProbeType()); + } + + /* Tool Mapping */ + { + response.cat(",\"tools\":["); + for(Tool *tool=toolList; tool != NULL; tool = tool->Next()) + { + // Heaters + response.cat("{\"heaters\":["); + for(uint8_t heater=0; heater<tool->HeaterCount(); heater++) + { + response.catf("%d", tool->Heater(heater)); + if (heater < tool->HeaterCount() - 1) + { + response.cat(","); + } + } + + // Extruder drives + response.cat("],\"drives\":["); + for(uint8_t drive=0; drive<tool->DriveCount(); drive++) + { + response.catf("%d", tool->Drive(drive)); + if (drive < tool->DriveCount() - 1) + { + response.cat(","); + } + } + + // Do we have any more tools? + if (tool->Next() != NULL) + { + response.cat("]},"); + } + else + { + response.cat("]}"); + } + } + response.cat("]"); + } + } + else if (type == 3) + { + // Current Layer + response.catf(",\"currentLayer\":%d", currentLayer); + + // Current Layer Time + response.catf(",\"currentLayerTime\":%.1f", (lastLayerTime > 0.0) ? (platform->Time() - lastLayerTime) : 0.0); + + // Raw Extruder Positions + response.catf("],\"extrRaw\":"); // announce the extruder positions + ch = '['; + for (size_t drive = 0; drive < reprap.GetExtrudersInUse(); drive++) // loop through extruders + { + response.catf("%c%.1f", ch, gCodes->GetRawExtruderPosition(drive)); + ch = ','; + } + + // Fraction of file printed + response.catf("],\"fractionPrinted\":%.1f", (gCodes->PrintingAFile()) ? (gCodes->FractionOfFilePrinted() * 100.0) : 0.0); + + // First Layer Duration + response.catf(",\"firstLayerDuration\":%.1f", firstLayerDuration); + + // First Layer Height + response.catf(",\"firstLayerHeight\":%.2f", firstLayerHeight); + + // Print Duration + response.catf(",\"printDuration\":%.1f", (printStartTime > 0.0) ? (platform->Time() - printStartTime) : 0.0); + + // Warm-Up Time + response.catf(",\"warmUpDuration\":%.1f", warmUpDuration); + + /* Print Time Estimations */ + { + // Based on file progress + response.catf(",\"timesLeft\":{\"file\":%.1f", EstimateTimeLeft(0)); + + // Based on filament usage + response.catf(",\"filament\":%.1f", EstimateTimeLeft(1)); + + // Based on layers + response.catf(",\"layer\":%.1f}", EstimateTimeLeft(2)); + } + } + + response.cat("}"); +} + // Get the JSON status response for the web server or M105 command. // Type 0 is the old-style webserver status response (we should be able to bet rid of this soon). // Type 1 is the new-style webserver status response. // Type 2 is the M105 S2 response, which is like the new-style status response but some fields are omitted. // Type 3 is the M105 S3 response, which is like the M105 S2 response except that static values are also included. -// 'seq' is the response sequence number, not needed for the type 2 response because that field is omitted. -void RepRap::GetStatusResponse(StringRef& response, uint8_t type) const +// 'seq' is the response sequence number, if it is not -1 and we have a higher sequence number then we send the gcode response +void RepRap::GetLegacyStatusResponse(StringRef& response, uint8_t type, int seq) const { - const GCodes *gc = reprap.GetGCodes(); if (type != 0) { // New-style status request // Send the printing/idle status char ch = (processingConfig) ? 'C' : (reprap.IsStopped()) ? 'S' - : (gc->PrintingAFile()) ? 'P' + : (gCodes->PrintingAFile()) ? 'P' : 'I'; response.printf("{\"status\":\"%c\",\"heaters\":", ch); @@ -573,14 +1017,14 @@ void RepRap::GetStatusResponse(StringRef& response, uint8_t type) const ch = '['; for (int8_t drive = 0; drive < reprap.GetExtrudersInUse(); drive++) // loop through extruders { - response.catf("%c%.1f", ch, gc->GetExtruderPosition(drive)); + response.catf("%c%.1f", ch, gCodes->GetRawExtruderPosition(drive)); ch = ','; } response.cat("]"); // Send the speed and extruder override factors - response.catf(",\"sfactor\":%.2f,\"efactor\":", gc->GetSpeedFactor() * 100.0); - const float *extrusionFactors = gc->GetExtrusionFactors(); + response.catf(",\"sfactor\":%.2f,\"efactor\":", gCodes->GetSpeedFactor() * 100.0); + const float *extrusionFactors = gCodes->GetExtrusionFactors(); for (unsigned int i = 0; i < reprap.GetExtrudersInUse(); ++i) { response.catf("%c%.2f", (i == 0) ? '[' : ',', extrusionFactors[i] * 100.0); @@ -597,7 +1041,7 @@ void RepRap::GetStatusResponse(StringRef& response, uint8_t type) const // These are all returned in a single vector called "poll". // This is a poor choice of format because we can't easily tell which is which unless we already know the number of heaters and extruders. // RRP reversed the order at version 0.65 to send the positions before the heaters, but we haven't yet done that. - char c = (gc->PrintingAFile()) ? 'P' : 'I'; + char c = (gCodes->PrintingAFile()) ? 'P' : 'I'; response.printf("{\"poll\":[\"%c\",", c); // Printing for (int8_t heater = 0; heater < HEATERS; heater++) { @@ -636,22 +1080,22 @@ void RepRap::GetStatusResponse(StringRef& response, uint8_t type) const if (type != 0) { response.catf(",\"homed\":[%d,%d,%d]", - (gc->GetAxisIsHomed(0)) ? 1 : 0, - (gc->GetAxisIsHomed(1)) ? 1 : 0, - (gc->GetAxisIsHomed(2)) ? 1 : 0); + (gCodes->GetAxisIsHomed(0)) ? 1 : 0, + (gCodes->GetAxisIsHomed(1)) ? 1 : 0, + (gCodes->GetAxisIsHomed(2)) ? 1 : 0); } else { response.catf(",\"hx\":%d,\"hy\":%d,\"hz\":%d", - (gc->GetAxisIsHomed(0)) ? 1 : 0, - (gc->GetAxisIsHomed(1)) ? 1 : 0, - (gc->GetAxisIsHomed(2)) ? 1 : 0); + (gCodes->GetAxisIsHomed(0)) ? 1 : 0, + (gCodes->GetAxisIsHomed(1)) ? 1 : 0, + (gCodes->GetAxisIsHomed(2)) ? 1 : 0); } - if (gc->PrintingAFile()) + if (gCodes->PrintingAFile()) { // Send the fraction printed - response.catf(",\"fraction_printed\":%.4f", max<float>(0.0, gc->FractionOfFilePrinted())); + response.catf(",\"fraction_printed\":%.4f", max<float>(0.0, gCodes->FractionOfFilePrinted())); } response.cat(",\"message\":"); @@ -660,22 +1104,43 @@ void RepRap::GetStatusResponse(StringRef& response, uint8_t type) const if (type < 2) { response.catf(",\"buff\":%u", webserver->GetGcodeBufferSpace()); // send the amount of buffer space available for gcodes - response.catf(",\"seq\":%u", webserver->GetReplySeq()); // send the response sequence number + } + + if (type < 2 || (seq != -1 && replySeq > seq)) + { + response.catf(",\"seq\":%u", replySeq); // send the response sequence number // Send the response to the last command. Do this last because it is long and may need to be truncated. response.cat(",\"resp\":"); - EncodeString(response, webserver->GetGcodeReply().Pointer(), 2, true); + EncodeString(response, GetGcodeReply().Pointer(), 2, true); } - else if (type == 3) + + if (type == 3) { // Add the static fields. For now this is just geometry and the machine name, but other fields could be added e.g. axis lengths. response.catf(",\"geometry\":\"%s\",\"myName\":", move->IsDeltaMode() ? "delta" : "cartesian"); - EncodeString(response, webserver->GetName(), 2, false); + EncodeString(response, myName, 2, false); } response.cat("}"); } +// Copy some parameter text, stopping at the first control character or when the destination buffer is full, and removing trailing spaces +void RepRap::CopyParameterText(const char* src, char *dst, size_t length) +{ + size_t i; + for (i = 0; i + 1 < length && src[i] >= ' '; ++i) + { + dst[i] = src[i]; + } + // Remove any trailing spaces + while (i > 0 && dst[i - 1] == ' ') + { + --i; + } + dst[i] = 0; +} + // Encode a string in JSON format and append it to a string buffer, truncating it if necessary to leave the specified amount of room void RepRap::EncodeString(StringRef& response, const char* src, size_t spaceToLeave, bool allowControlChars) { @@ -732,7 +1197,7 @@ void RepRap::EncodeString(StringRef& response, const char* src, size_t spaceToLe void RepRap::GetNameResponse(StringRef& response) const { response.copy("{\"myName\":"); - EncodeString(response, webserver->GetName(), 2, false); + EncodeString(response, myName, 2, false); response.cat("}"); } @@ -820,12 +1285,339 @@ void RepRap::StartingFilePrint(const char *filename) fileBeingPrinted[ARRAY_UPB(fileBeingPrinted)] = 0; } +void RepRap::Beep(int freq, int ms) +{ + if (gCodes->HaveAux()) + { + // If there is an LCD device present, make it beep + platform->Beep(freq, ms); + } + else + { + // Otherwise queue it until the webserver can process it + beepFrequency = freq; + beepDuration = ms; + } +} + void RepRap::SetMessage(const char *msg) { strncpy(message, msg, maxMessageLength); message[maxMessageLength] = 0; } +void RepRap::MessageToGCodeReply(const char *message) +{ + gcodeReply.copy(message); + ++replySeq; +} + +void RepRap::AppendMessageToGCodeReply(const char *message) +{ + gcodeReply.cat(message); +} + +void RepRap::AppendCharToStatusResponse(const char c) +{ + gcodeReply.catf("%c", c); +} + +bool RepRap::NoPasswordSet() const +{ + return (!password[0] || StringEquals(password, DEFAULT_PASSWORD)); +} + +bool RepRap::CheckPassword(const char *pw) const +{ + return StringEquals(pw, password); +} + +void RepRap::SetPassword(const char* pw) +{ + // Users sometimes put a tab character between the password and the comment, so allow for this + CopyParameterText(pw, password, ARRAY_SIZE(password)); +} + +const char *RepRap::GetName() const +{ + return myName; +} + +void RepRap::SetName(const char* nm) +{ + // Users sometimes put a tab character between the machine name and the comment, so allow for this + CopyParameterText(nm, myName, ARRAY_SIZE(myName)); +} + +// The following methods keep track of the current print + +void RepRap::UpdatePrintProgress() +{ + if (gCodes->IsPausing() || gCodes->IsPaused() || gCodes->IsResuming()) + { + return; + } + + if (gCodes->PrintingAFile()) + { + // May have just started a print, see if we're heating up + if (warmUpDuration == 0.0) + { + // When a new print starts, the total (raw) extruder positions are zeroed + float totalRawFilament = 0.0; + for (size_t extruder=0; extruder<DRIVES - AXES; extruder++) + { + totalRawFilament += gCodes->GetRawExtruderPosition(extruder); + } + + // See if at least one heater is active and set + bool heatersAtHighTemperature = false; + for (uint8_t heater=E0_HEATER; heater<HEATERS; heater++) + { + if (heat->GetStatus(heater) == Heat::HS_active && + heat->GetActiveTemperature(heater) > TEMPERATURE_LOW_SO_DONT_CARE && + heat->HeaterAtSetTemperature(heater)) + { + heatersAtHighTemperature = true; + break; + } + } + + if (heatersAtHighTemperature && totalRawFilament != 0.0) + { + lastLayerTime = platform->Time(); + warmUpDuration = lastLayerTime - printStartTime; + + if (fileInfoDetected && currentFileInfo.layerHeight > 0.0) { + currentLayer = 1; + } + } + } + // Looks like the print has started + else if (currentLayer > 0) + { + float liveCoords[DRIVES + 1]; + move->LiveCoordinates(liveCoords); + + // See if we can determine the first layer height (must be smaller than the nozzle diameter) + if (firstLayerHeight == 0.0) + { + if (liveCoords[Z_AXIS] < NOZZLE_DIAMETER && !gCodes->DoingFileMacro()) + { + firstLayerHeight = liveCoords[Z_AXIS]; + } + } + // Then check if we've finished the first layer + else if (firstLayerDuration == 0.0) + { + if (liveCoords[Z_AXIS] > firstLayerHeight * 1.05) // allow some tolerance for transform operations + { + firstLayerFilament = 0.0; + for (size_t extruder=0; extruder<DRIVES - AXES; extruder++) + { + firstLayerFilament += gCodes->GetRawExtruderPosition(extruder); + } + firstLayerDuration = platform->Time() - lastLayerTime; + firstLayerProgress = gCodes->FractionOfFilePrinted(); + } + } + // We have enough values to estimate the following layer heights + else if (currentFileInfo.objectHeight > 0.0) + { + unsigned int estimatedLayer = round((liveCoords[Z_AXIS] - firstLayerHeight) / currentFileInfo.layerHeight) + 1; + if (estimatedLayer == currentLayer + 1) // on layer change + { + // Record untainted extruder positions for filament-based estimation + float extrRawTotal = 0.0; + for(uint8_t extruder=0; extruder<DRIVES - AXES; extruder++) + { + extrRawTotal += gCodes->GetRawExtruderPosition(extruder); + } + + const float now = platform->Time(); + unsigned int remainingLayers; + remainingLayers = round((currentFileInfo.objectHeight - firstLayerHeight) / currentFileInfo.layerHeight) + 1; + remainingLayers -= currentLayer; + + if (currentLayer > 1) + { + // Record a new set + if (numLayerSamples < MAX_LAYER_SAMPLES) + { + layerDurations[numLayerSamples] = now - lastLayerTime; + if (!numLayerSamples) + { + filamentUsagePerLayer[numLayerSamples] = extrRawTotal - firstLayerFilament; + } + else + { + filamentUsagePerLayer[numLayerSamples] = extrRawTotal - lastLayerFilament; + } + fileProgressPerLayer[numLayerSamples] = gCodes->FractionOfFilePrinted(); + numLayerSamples++; + } + else + { + for(unsigned int i=1; i<MAX_LAYER_SAMPLES; i++) + { + layerDurations[i - 1] = layerDurations[i]; + filamentUsagePerLayer[i - 1] = filamentUsagePerLayer[i]; + fileProgressPerLayer[i - 1] = fileProgressPerLayer[i]; + } + + layerDurations[MAX_LAYER_SAMPLES - 1] = now - lastLayerTime; + filamentUsagePerLayer[MAX_LAYER_SAMPLES - 1] = extrRawTotal - lastLayerFilament; + fileProgressPerLayer[MAX_LAYER_SAMPLES - 1] = gCodes->FractionOfFilePrinted(); + } + } + + // Update layer-based estimation times + float avgLayerTime, avgLayerDelta = 0.0; + if (numLayerSamples) + { + avgLayerTime = 0.0; + for(unsigned int layer=0; layer<numLayerSamples; layer++) + { + avgLayerTime += layerDurations[layer]; + if (layer) + { + avgLayerDelta += layerDurations[layer] - layerDurations[layer - 1]; + } + } + avgLayerTime /= numLayerSamples; + avgLayerDelta /= numLayerSamples; + } + else + { + avgLayerTime = firstLayerDuration * FIRST_LAYER_SPEED_FACTOR; + } + + layerEstimatedTimeLeft = (avgLayerTime * remainingLayers) - (avgLayerDelta * remainingLayers); + if (layerEstimatedTimeLeft < 0.0) + { + layerEstimatedTimeLeft = avgLayerTime * remainingLayers; + } + + // TODO: maybe move other estimation methods here too? + // And move whole estimation code to a separate class? + + // Set new layer values + currentLayer = estimatedLayer; + lastLayerTime = now; + lastLayerFilament = extrRawTotal; + } + } + } + } + else if (printStartTime > 0.0 && move->NoLiveMovement()) + { + currentLayer = numLayerSamples = 0; + firstLayerDuration = firstLayerHeight = firstLayerFilament = firstLayerProgress = 0.0; + layerEstimatedTimeLeft = printStartTime = warmUpDuration = 0.0; + lastLayerTime = lastLayerFilament = 0.0; + } +} + +float RepRap::EstimateTimeLeft(uint8_t method) const +{ + // We can't provide an estimation if we're not printing (yet) + if (!gCodes->PrintingAFile() || (fileInfoDetected && currentFileInfo.numFilaments && warmUpDuration == 0.0)) + { + return 0.0; + } + + // Take into account the first layer time only if we haven't got any other samples + float realPrintDuration = (platform->Time() - printStartTime) - warmUpDuration; + if (numLayerSamples) + { + realPrintDuration -= firstLayerDuration; + } + + // Actual estimations + switch (method) + { + case 0: // File-Based + { + // Provide rough estimation only if we haven't collected any layer samples + float fractionPrinted = gCodes->FractionOfFilePrinted(); + if (!numLayerSamples || !fileInfoDetected || currentFileInfo.objectHeight == 0.0) + { + return realPrintDuration * (1.0 / fractionPrinted) - realPrintDuration; + } + + // Each layer takes time to achieve more file progress, so take an average over our samples + float avgSecondsByProgress = 0.0, lastLayerProgress = 0.0; + for(unsigned int layer=0; layer<numLayerSamples; layer++) + { + avgSecondsByProgress += layerDurations[layer] / (fileProgressPerLayer[layer] - lastLayerProgress); + lastLayerProgress = fileProgressPerLayer[layer]; + } + avgSecondsByProgress /= numLayerSamples; + + // Then we know how many seconds it takes to finish 1% and we know how much file progress is left + return avgSecondsByProgress * (1.0 - fractionPrinted); + } + + case 1: // Filament-Based + { + // Need some file information, otherwise this method won't work + if (!fileInfoDetected || !currentFileInfo.numFilaments) + { + return 0.0; + } + + // Sum up the filament usage and the filament needed + float totalFilamentNeeded = 0.0; + float extrRawTotal = 0.0; + for (size_t extruder=0; extruder < DRIVES - AXES; extruder++) + { + totalFilamentNeeded += currentFileInfo.filamentNeeded[extruder]; + extrRawTotal += gCodes->GetRawExtruderPosition(extruder); + } + + // If we have a reasonable amount of filament extruded, calculate estimated times left + if (totalFilamentNeeded > 0.0 && extrRawTotal > totalFilamentNeeded * ESTIMATION_MIN_FILAMENT_USAGE) + { + if (firstLayerFilament == 0.0) + { + return realPrintDuration * (totalFilamentNeeded - extrRawTotal) / extrRawTotal; + } + + float filamentRate; + if (numLayerSamples) + { + filamentRate = 0.0; + for (unsigned int i=0; i<numLayerSamples; i++) + { + filamentRate += filamentUsagePerLayer[i] / layerDurations[i]; + } + filamentRate /= numLayerSamples; + } + else + { + filamentRate = firstLayerFilament / firstLayerDuration; + } + + return (totalFilamentNeeded - extrRawTotal) / filamentRate; + } + break; + } + + case 2: // Layer-Based + if (layerEstimatedTimeLeft > 0.0) + { + float timeLeft = layerEstimatedTimeLeft - (platform->Time() - lastLayerTime); + if (timeLeft > 0.0) + { + return timeLeft; + } + } + break; + } + + return 0.0; +} + void RepRap::GetExtruderCapabilities(bool canDrive[], const bool directions[]) const { for (uint8_t extruder=0; extruder<DRIVES - AXES; extruder++) @@ -863,44 +1655,6 @@ void RepRap::ClearTemperatureFault(int8_t wasDudHeater) } } -void RepRap::SetDebug(Module m, bool enable) -{ - if (enable) - { - debug |= (1 << m); - } - else - { - debug &= ~(1 << m); - } - PrintDebug(); -} - -void RepRap::SetDebug(bool enable) -{ - debug = (enable) ? 0xFFFF : 0; -} - -void RepRap::PrintDebug() -{ - if (debug != 0) - { - platform->Message(BOTH_MESSAGE, "Debugging enabled for modules:%s%s%s%s%s%s%s\n", - (debug & (1 << modulePlatform)) ? " Platform" : "", - (debug & (1 << moduleNetwork)) ? " Network" : "", - (debug & (1 << moduleWebserver)) ? " Webserver" : "", - (debug & (1 << moduleGcodes)) ? " GCodes" : "", - (debug & (1 << moduleMove)) ? " Move" : "", - (debug & (1 << moduleDda)) ? " DDA" : "", - (debug & (1 << moduleHeat)) ? " Heat" : "" - ); - } - else - { - platform->Message(BOTH_MESSAGE, "Debugging disabled\n"); - } -} - //************************************************************************************************* // StringRef class member implementations diff --git a/RepRapFirmware.h b/RepRapFirmware.h index 557883f0..f6ac0634 100644 --- a/RepRapFirmware.h +++ b/RepRapFirmware.h @@ -29,10 +29,18 @@ Licence: GPL // Module numbers, used for diagnostics and debug enum Module { - modulePlatform = 0, moduleNetwork = 1, moduleWebserver = 2, moduleGcodes = 3, moduleMove = 4, moduleHeat = 5, moduleDda = 6, + modulePlatform = 0, + moduleNetwork = 1, + moduleWebserver = 2, + moduleGcodes = 3, + moduleMove = 4, + moduleHeat = 5, + moduleDda = 6, noModule = 15 }; +extern const char *moduleName[]; + // Warn of what's to come, so we can use pointers to classes... class Network; @@ -30,15 +30,24 @@ class RepRap RepRap(); void EmergencyStop(); void Init(); + Module GetSpinningModule() const; void Spin(); void Exit(); void Interrupt(); void Diagnostics(); void Timing(); + bool Debug(Module module) const; void SetDebug(Module m, bool enable); void SetDebug(bool enable); void PrintDebug(); + + bool NoPasswordSet() const; + bool CheckPassword(const char* pw) const; + void SetPassword(const char* pw); + const char *GetName() const; + void SetName(const char* nm); + void AddTool(Tool* t); void SelectTool(int toolNumber); void StandbyTool(int toolNumber); @@ -46,61 +55,108 @@ class RepRap Tool* GetTool(int toolNumber); Tool* GetToolByDrive(int driveNumber); void SetToolVariables(int toolNumber, float* standbyTemperatures, float* activeTemperatures); + void AllowColdExtrude(); void DenyColdExtrude(); - bool ColdExtrude() const; + bool ColdExtrude(); + void GetExtruderCapabilities(bool canDrive[], const bool directions[]) const; void PrintTool(int toolNumber, StringRef& reply) const; void FlagTemperatureFault(int8_t dudHeater); void ClearTemperatureFault(int8_t wasDudHeater); + Platform* GetPlatform() const; Move* GetMove() const; Heat* GetHeat() const; GCodes* GetGCodes() const; Network* GetNetwork() const; Webserver* GetWebserver() const; + void Tick(); - bool IsStopped() const; uint16_t GetTicksInSpinState() const; + bool IsStopped() const; + uint16_t GetExtrudersInUse() const; uint16_t GetHeatersInUse() const; - void GetStatusResponse(StringRef& response, uint8_t type) const; + + void GetStatusResponse(StringRef& response, uint8_t type, bool forWebserver); + void GetLegacyStatusResponse(StringRef &response, uint8_t type, int seq) const; void GetNameResponse(StringRef& response) const; void GetFilesResponse(StringRef& response, const char* dir) const; void GetFileInfoResponse(StringRef& response, const char* filename) const; + void StartingFilePrint(const char *filename); + void Beep(int freq, int ms); void SetMessage(const char *msg); + void MessageToGCodeReply(const char *message); + void AppendMessageToGCodeReply(const char *message); + void AppendCharToStatusResponse(const char c); + + const StringRef& GetGcodeReply() const; + + static void CopyParameterText(const char* src, char *dst, size_t length); + private: + static void EncodeString(StringRef& response, const char* src, size_t spaceToLeave, bool allowControlChars); + void UpdatePrintProgress(); + float EstimateTimeLeft(uint8_t method) const; + Platform* platform; Network* network; Move* move; Heat* heat; GCodes* gCodes; Webserver* webserver; + Tool* toolList; Tool* currentTool; + uint16_t activeExtruders; + uint16_t activeHeaters; + bool coldExtrude; + uint16_t ticksInSpinState; - Module currentModule; - uint16_t debug; + Module spinningModule; float fastLoop, slowLoop; float lastTime; + + uint16_t debug; bool stopped; bool active; bool resetting; bool processingConfig; - uint16_t activeExtruders; - uint16_t activeHeaters; - bool coldExtrude; - // File information about the file being printed - bool fileInfoDetected; - char fileBeingPrinted[255]; - GcodeFileInfo currentFileInfo; - float printStartTime; - char message[maxMessageLength + 1]; + char password[SHORT_STRING_LENGTH + 1]; + char myName[SHORT_STRING_LENGTH + 1]; + + bool fileInfoDetected; + char fileBeingPrinted[255]; + GcodeFileInfo currentFileInfo; + + int beepFrequency, beepDuration; + char message[SHORT_STRING_LENGTH + 1]; + + char gcodeReplyBuffer[GCODE_REPLY_LENGTH]; + StringRef gcodeReply; + unsigned int replySeq; + + float printStartTime; + unsigned int currentLayer; + float warmUpDuration; + + float firstLayerDuration; + float firstLayerHeight; + float firstLayerFilament; + float firstLayerProgress; + + float lastLayerTime, lastLayerFilament; + unsigned int numLayerSamples; + float layerDurations[MAX_LAYER_SAMPLES]; + float filamentUsagePerLayer[MAX_LAYER_SAMPLES]; + float fileProgressPerLayer[MAX_LAYER_SAMPLES]; + float layerEstimatedTimeLeft; }; inline Platform* RepRap::GetPlatform() const { return platform; } @@ -109,17 +165,20 @@ inline Heat* RepRap::GetHeat() const { return heat; } inline GCodes* RepRap::GetGCodes() const { return gCodes; } inline Network* RepRap::GetNetwork() const { return network; } inline Webserver* RepRap::GetWebserver() const { return webserver; } +inline Module RepRap::GetSpinningModule() const { return spinningModule; } inline bool RepRap::Debug(Module m) const { return debug & (1 << m); } inline Tool* RepRap::GetCurrentTool() { return currentTool; } inline uint16_t RepRap::GetExtrudersInUse() const { return activeExtruders; } inline uint16_t RepRap::GetHeatersInUse() const { return activeHeaters; } -inline bool RepRap::ColdExtrude() const { return coldExtrude; } +inline bool RepRap::ColdExtrude() { return coldExtrude; } inline void RepRap::AllowColdExtrude() { coldExtrude = true; } inline void RepRap::DenyColdExtrude() { coldExtrude = false; } inline void RepRap::Interrupt() { move->Interrupt(); } inline bool RepRap::IsStopped() const { return stopped; } inline uint16_t RepRap::GetTicksInSpinState() const { return ticksInSpinState; } +inline const StringRef& RepRap::GetGcodeReply() const { return gcodeReply; } + #endif diff --git a/SD-image/sys-Ormerod1/config.g b/SD-image/sys-Ormerod1/config.g index f9a87def..31f4e165 100644 --- a/SD-image/sys-Ormerod1/config.g +++ b/SD-image/sys-Ormerod1/config.g @@ -1,5 +1,4 @@ -; Configuration file for RepRap Ormerod -; RepRapPro Ltd +; Ormerod 1 config file for dc42 Duet firmware M111 S0 ; Debug off M550 PMy Ormerod ; Machine name (can be anything you like) M551 Preprap ; Machine password (currently not used) @@ -17,14 +16,14 @@ M906 X800 Y1000 Z800 E800 ; Set motor currents (mA) M563 P1 D0 H1 ; Define tool 1 G10 P1 S0 R0 ; Set tool 1 operating and standby temperatures M92 E420 ; Set extruder steps per mm (single nozzle) -;*** If you have a dual-nozzle build, remove ot comment out the previous line, and un-comment the following 3 lines +;*** If you have a dual-nozzle build, remove or comment out the previous line, and un-comment the following 3 lines ;M563 P2 D1 H2 ; Define tool 2 ;G10 P2 S0 R0 ; Set tool 2 operating and standby temperatures ;M92 E420:420 ; Set extruder steps/mm (dual nozzle) ;*** If you have a modulated IR probe without on-board microcontroller, change P1 to P2 in the following M558 P1 ; Use an unmodulated Z probe or an intelligent Z probe G31 Z1.20 P500 ; Set the probe height and threshold (put your own values here) -;*** If you have a Duet 0.7 board, change R1000 to R4700 to the following M305 commands +;*** If you have a Duet board with 4.7K thermistor series resistors, change R1000 to R4700 to the following M305 commands M305 P0 R1000 H0 L0 ; Put your own H and/or L values here to set the bed thermistor ADC correction M305 P1 R1000 H0 L0 ; Put your own H and/or L values here to set the first nozzle thermistor ADC correction M305 P2 R1000 H0 L0 ; Put your own H and/or L values here to set the second nozzle thermistor ADC correction @@ -40,4 +39,4 @@ M201 X800 Y800 Z15 E1000 ; Accelerations (mm/s^2) M203 X15000 Y15000 Z100 E3600 ; Maximum speeds (mm/min) M566 X600 Y600 Z30 E20 ; Minimum speeds mm/minute M208 X214 Y210 ; set axis maxima (adjust to suit your machine) -M208 X-8 S1 ; set axis minimum (adjust to make X=0 the edge of the bed) +M208 X-8 Y0 S1 ; set axis minimum (adjust to make X=0 the edge of the bed) diff --git a/SD-image/sys-Ormerod1/homeall.g b/SD-image/sys-Ormerod1/homeall.g index 9135a5a0..6265ec01 100644 --- a/SD-image/sys-Ormerod1/homeall.g +++ b/SD-image/sys-Ormerod1/homeall.g @@ -1,9 +1,16 @@ +; Ormerod 1 homeall file for use with dc42 Duet firmware +; Adjust the bed upper and lower limits in config.g (M208 commands) to get the correct homing positions G91 G1 Z4 F200 -G1 X-240 F2000 S1 -G1 X4 F500 -G1 X-10 S1 -G1 Y220 F2000 S1 +G1 X-240 Y240 F2000 S1 +G1 X4 Y-4 F500 +G1 X-10 Y10 S1 G90 -G1 X100 Y105 F12000 +; Adjust the XY coordinates in the following to place the IR sensor over a suitable spot +; If you are using a dc42 IR sensor then you can change the cootdinates to be near the centre of the bed +G1 X45 Y0 F2000 G30 +; This file leaves the head at the zprobe trigger height so that you can slip a piece of paper under it and then do G0 Z0 to check the height. +; If you prefer to send the printer to X0Y0Z0, un-comment the folloeing lines +;G1 X0 Y0 F5000 +;G1 Z0 diff --git a/SD-image/sys-Ormerod1/homex.g b/SD-image/sys-Ormerod1/homex.g index 7c34602e..27b407f2 100644 --- a/SD-image/sys-Ormerod1/homex.g +++ b/SD-image/sys-Ormerod1/homex.g @@ -1,3 +1,4 @@ +; X axis homing file for dc42 Duet firmware G91 G1 Z4 F200 G1 X-240 F2000 S1 diff --git a/SD-image/sys-Ormerod1/homey.g b/SD-image/sys-Ormerod1/homey.g index 381ac344..8eb677bd 100644 --- a/SD-image/sys-Ormerod1/homey.g +++ b/SD-image/sys-Ormerod1/homey.g @@ -1,8 +1,8 @@ +; Omerod 1 Y homing file for dc42 Duet firmware G91 -G1 Z2 F200 -G1 Y220 F2000 S1 -G90 -G1 Y0 F12000 -G91 -G1 Z-2 F200 +G1 Z4 F200 +G1 Y240 F2000 S1 +G1 Y-4 F500 +G1 Y10 S1 +G1 Z-4 F200 G90 diff --git a/SD-image/sys-Ormerod1/pause.g b/SD-image/sys-Ormerod1/pause.g new file mode 100644 index 00000000..c64f0ed8 --- /dev/null +++ b/SD-image/sys-Ormerod1/pause.g @@ -0,0 +1,5 @@ +; Pause macro file +G91 +G1 Z5 F5000 +G90 +G1 X0 Y0 F5000 diff --git a/SD-image/sys-Ormerod1/resume.g b/SD-image/sys-Ormerod1/resume.g new file mode 100644 index 00000000..e13db2f8 --- /dev/null +++ b/SD-image/sys-Ormerod1/resume.g @@ -0,0 +1,4 @@ +; Resume macro file +G91 +;G1 Z-5 F5000 +G90 diff --git a/SD-image/sys-Ormerod2/config.g b/SD-image/sys-Ormerod2/config.g index f078bdcd..3d52b140 100644 --- a/SD-image/sys-Ormerod2/config.g +++ b/SD-image/sys-Ormerod2/config.g @@ -1,5 +1,4 @@ -; Configuration file for RepRap Ormerod -; RepRapPro Ltd +; Ormerod 2 config file for dc42 Duet firmware M111 S0 ; Debug off M550 PMy Ormerod ; Machine name (can be anything you like) M551 Preprap ; Machine password (currently not used) @@ -17,14 +16,14 @@ M906 X800 Y1000 Z800 E800 ; Set motor currents (mA) M563 P1 D0 H1 ; Define tool 1 G10 P1 S0 R0 ; Set tool 1 operating and standby temperatures M92 E420 ; Set extruder steps per mm (single nozzle) -;*** If you have a dual-nozzle build, remove ot comment out the previous line, and un-comment the following 3 lines +;*** If you have a dual-nozzle build, remove or comment out the previous line, and un-comment the following 3 lines ;M563 P2 D1 H2 ; Define tool 2 ;G10 P2 S0 R0 ; Set tool 2 operating and standby temperatures ;M92 E420:420 ; Set extruder steps/mm (dual nozzle) -;*** If you have a modulated IR probe without on-board microcontroller, change P1 to P2 in the following -M558 P1 ; Use an unmodulated Z probe or an intelligent Z probe +;*** If you have a modulated IR probe with on-board microcontroller, change P2 to P1 in the following +M558 P2 ; Use a simple modulated Z probe (change to P1 for an intelligent Z probe) G31 Z1.20 P500 ; Set the probe height and threshold (put your own values here) -;*** If you have a Duet 0.7 board, change R1000 to R4700 to the following M305 commands +;*** If you have a Duet board with 4.7K thermistor series resistors, change R1000 to R4700 to the following M305 commands M305 P0 R1000 H0 L0 ; Put your own H and/or L values here to set the bed thermistor ADC correction M305 P1 R1000 H0 L0 ; Put your own H and/or L values here to set the first nozzle thermistor ADC correction M305 P2 R1000 H0 L0 ; Put your own H and/or L values here to set the second nozzle thermistor ADC correction @@ -40,4 +39,4 @@ M201 X800 Y800 Z15 E1000 ; Accelerations (mm/s^2) M203 X15000 Y15000 Z100 E3600 ; Maximum speeds (mm/min) M566 X600 Y600 Z30 E20 ; Minimum speeds mm/minute M208 X214 Y210 ; set axis maxima (adjust to suit your machine) -M208 X-8 S1 ; set axis minimum (adjust to make X=0 the edge of the bed) +M208 X-8 Y0 S1 ; set axis minimum (adjust to make X=0 the edge of the bed) diff --git a/SD-image/sys-Ormerod2/homeall.g b/SD-image/sys-Ormerod2/homeall.g index 03194cb0..b9863f06 100644 --- a/SD-image/sys-Ormerod2/homeall.g +++ b/SD-image/sys-Ormerod2/homeall.g @@ -1,25 +1,16 @@ +; Ormerod 2 homeall file for use with dc42 Duet firmware +; Adjust the bed upper and lower limits in config.g (M208 commands) to get the correct homing positions G91 -G1 Z5 F200 +G1 Z4 F200 +G1 X-240 Y-240 F2000 S1 +G1 X4 Y4 F500 +G1 X-10 Y-10 S1 G90 -M558 P1 -G1 X-240 F2000 S1 -G92 X0 -G1 X3 F500 -G1 X-30 S1 -G92 X0 -G1 X15 F500 ; adjust the X value to put the nozzle on the edge of the bed -G92 X0 -M558 P2 -G1 X45 F2000 -G92 Y0 -G1 Y-240 F2000 S1 -G92 Y0 -G1 Y3 F200 -G1 Y-30 S1 -G92 Y0 -G1 Y3 F500 ; adjust the Y value to put the nozzle on the edge of the bed -G92 Y0 +; Adjust the XY coordinates in the following to place the IR sensor over a suitable spot +; If you are using a dc42 IR sensor then you can change the cootdinates to be near the centre of the bed +G1 X45 Y0 F2000 G30 -G1 Z5 F200 -G1 X0 Y0 -G1 Z0 +; This file leaves the head at the zprobe trigger height so that you can slip a piece of paper under it and then do G0 Z0 to check the height. +; If you prefer to send the printer to X0Y0Z0, un-comment the folloeing lines +;G1 X0 Y0 F5000 +;G1 Z0 diff --git a/SD-image/sys-Ormerod2/homex.g b/SD-image/sys-Ormerod2/homex.g index 819af81e..27b407f2 100644 --- a/SD-image/sys-Ormerod2/homex.g +++ b/SD-image/sys-Ormerod2/homex.g @@ -1,15 +1,8 @@ +; X axis homing file for dc42 Duet firmware G91 -G1 Z5 F200 -G90 -M558 P1 +G1 Z4 F200 G1 X-240 F2000 S1 -G92 X0 -G1 X3 F500 -G1 X-30 S1 -G92 X0 -G1 X15 F500 ; adjust the X value to put the nozzle on the edge of the bed -G92 X0 -M558 P2 -G91 -G1 Z-5 F200 +G1 X4 F500 +G1 X-10 S1 +G1 Z-4 F200 G90 diff --git a/SD-image/sys-Ormerod2/homey.g b/SD-image/sys-Ormerod2/homey.g index b73e06e3..2820fc26 100644 --- a/SD-image/sys-Ormerod2/homey.g +++ b/SD-image/sys-Ormerod2/homey.g @@ -1,16 +1,8 @@ +; Omerod 2 Y homing file for dc42 Duet firmware G91 -G1 Z5 F200 -G1 X20 F2000 -G90 -G92 Y0 -G1 Y-250 F2000 S1 -G92 Y0 -G1 Y3 F200 -G1 Y-30 F200 S1 -G92 Y0 -G1 Y3 F500 ; adjust the Y value to put the nozzle on the edge of the bed -G92 Y0 -G91 -G1 X-20 F2000 -G1 Z-5 F200 +G1 Z4 F200 +G1 Y-240 F2000 S1 +G1 Y4 F500 +G1 Y-10 S1 +G1 Z-4 F200 G90 diff --git a/Webserver.cpp b/Webserver.cpp index 556bb95f..29b1c0fc 100644 --- a/Webserver.cpp +++ b/Webserver.cpp @@ -4,12 +4,10 @@ This class serves a single-page web applications to the attached network. This page forms the user's interface with the RepRap machine. This software interprests returned values from the page and uses it - to Generate G Codes, which it sends to the RepRap. It also collects values from the RepRap like + to generate G Codes, which it sends to the RepRap. It also collects values from the RepRap like temperature and uses those to construct the web page. - The page itself - reprap.htm - uses Knockout.js and Jquery.js. See: - - http://knockoutjs.com/ + The page itself - reprap.htm - uses Jquery.js to perform AJAX. See: http://jquery.com/ @@ -31,32 +29,23 @@ SD card), and the following. These all start with "/rr_". Ordinary files used for the web interface must not have names starting "/rr_" or they will not be found. - rr_connect Sent by the web interface software to establish an initial connection, indicating that + rr_connect?password=xxx + Sent by the web interface software to establish an initial connection, indicating that any state variables relating to the web interface (e.g. file upload in progress) should - be reset. Returns the same response as rr_status. - - rr_poll Returns the old-style status response. Not recommended because all the position, - extruder position and temperature variables are returned in a single array, which means - that the web interface has to know in advance how many heaters and extruders there are. - Provided only for backwards compatibility with older web interface software. Likely to - be removed in a future version. + be reset. This only happens if the password could be verified. rr_status New-style status response, in which temperatures, axis positions and extruder positions are returned in separate variables. Another difference is that extruder positions are - returned as absolute positions instead of relative to the previous gcode. + returned as absolute positions instead of relative to the previous gcode. A client + may also request different status responses by specifying the "type" keyword, followed + by a custom status response type. Also see "M105 S1". rr_files?dir=xxx Returns a listing of the filenames in the /gcode directory of the SD card. 'dir' is a directory path relative to the root of the SD card. If the 'dir' variable is not present, it defaults to the /gcode directory. - rr_axes Returns the axis lengths. - - rr_name Returns the machine name in variable myname. - - rr_password?password=xxx - Returns variable "password" having value "right" if xxx is the correct password and - "wrong" otherwise. + rr_reply Returns the last-known G-code reply as plain text (not encapsulated as JSON). rr_upload_begin?name=xxx Indicates that we wish to upload the specified file. xxx is the filename relative @@ -100,33 +89,27 @@ const float pasvPortTimeout = 10.0; // seconds to wait for the FTP data po // Constructor and initialisation -Webserver::Webserver(Platform* p) : platform(p), webserverActive(false), readingConnection(NULL), - gcodeReply(gcodeReplyBuffer, ARRAY_SIZE(gcodeReplyBuffer)) +Webserver::Webserver(Platform* p, Network *n) : platform(p), network(n), + webserverActive(false), readingConnection(NULL) { - httpInterpreter = new HttpInterpreter(p, this); - ftpInterpreter = new FtpInterpreter(p, this); - telnetInterpreter = new TelnetInterpreter(p, this); + httpInterpreter = new HttpInterpreter(p, this, n); + ftpInterpreter = new FtpInterpreter(p, this, n); + telnetInterpreter = new TelnetInterpreter(p, this, n); } void Webserver::Init() { // initialise the webserver class - SetPassword(DEFAULT_PASSWORD); - SetName(DEFAULT_NAME); - gcodeReadIndex = gcodeWriteIndex = 0; lastTime = platform->Time(); longWait = lastTime; - gcodeReply[0] = 0; webserverActive = true; // initialise all protocol handlers httpInterpreter->ResetState(); + httpInterpreter->ResetSessions(); ftpInterpreter->ResetState(); telnetInterpreter->ResetState(); - - // Reinitialise the message file - //platform->GetMassStorage()->Delete(platform->GetWebDir(), MESSAGE_FILE); } @@ -135,14 +118,28 @@ void Webserver::Spin() { // Before we process an incoming Request, we must ensure that the webserver // is active and that all upload buffers are empty. + if (webserverActive && httpInterpreter->FlushUploadData() && ftpInterpreter->FlushUploadData()) { - Network *net = reprap.GetNetwork(); - NetworkTransaction *req = net->GetTransaction(readingConnection); + // Check if we can purge any HTTP sessions + + httpInterpreter->CheckSessions(); + + // We must ensure that we have exclusive access to LWIP + + if (!network->Lock()) + { + platform->ClassReport(longWait); + return; + } + + // See if we have new data to process + + NetworkTransaction *req = network->GetTransaction(readingConnection); if (req != NULL) { // Process incoming request - if (req->IsReady()) + if (!req->LostConnection()) { // I (zpl) have added support for two more protocols (FTP and Telnet), // so we must take care of the protocol type here. @@ -177,9 +174,9 @@ void Webserver::Spin() interpreter->ConnectionEstablished(); // Close this request unless ConnectionEstablished() has already used it for sending - if (req == net->GetTransaction(readingConnection)) + if (req == network->GetTransaction()) { - net->CloseTransaction(); + network->CloseTransaction(); } } // Graceful disconnects are handled here, because prior NetworkTransactions might still contain valid @@ -187,7 +184,7 @@ void Webserver::Spin() else if (status == disconnected) { // CloseRequest() will call the disconnect events and close the connection - net->CloseTransaction(); + network->CloseTransaction(); } // Fast upload for FTP connections else if (is_data_port) @@ -202,21 +199,27 @@ void Webserver::Spin() } else { - net->CloseTransaction(); + network->CloseTransaction(); } } - else + else if (req->DataLength() > 0) { platform->Message(HOST_MESSAGE, "Webserver: Closing invalid data connection\n"); readingConnection = NULL; - net->SendAndClose(NULL); + network->SendAndClose(NULL); } } + // Check if we need to send data to a Telnet client + else if (interpreter == telnetInterpreter && telnetInterpreter->HasRemainingData()) + { + network->SendAndClose(NULL, true); + telnetInterpreter->RemainingDataSent(); + } // Process other messages else { char c; - for (int i=0; i<500; i++) + for (uint16_t i=0; i<500; i++) { if (req->Read(c)) { @@ -231,22 +234,24 @@ void Webserver::Spin() else { // We ran out of data before finding a complete request. - // This happens when the incoming message length exceeds the TCP MSS. We need to process another packet on the same connection. + // This happens when the incoming message length exceeds the TCP MSS. + // We need to process another packet on the same connection. readingConnection = req->GetConnection(); - net->SendAndClose(NULL, true); + network->CloseTransaction(); break; } } } } - else if (req->LostConnection()) + else { - platform->Message(HOST_MESSAGE, "Webserver: Skipping zombie request\n"); - net->CloseTransaction(); + platform->Message(HOST_MESSAGE, "Webserver: Skipping zombie request with status %d\n", req->GetStatus()); + network->CloseTransaction(); } } - platform->ClassReport("Webserver", longWait, moduleWebserver); + network->Unlock(); + platform->ClassReport(longWait); } } @@ -254,7 +259,7 @@ void Webserver::Exit() { httpInterpreter->CancelUpload(); - platform->Message(HOST_MESSAGE, "Webserver class exited.\n"); + platform->Message(BOTH_MESSAGE, "Webserver class exited.\n"); webserverActive = false; } @@ -263,44 +268,6 @@ void Webserver::Diagnostics() platform->AppendMessage(BOTH_MESSAGE, "Webserver Diagnostics:\n"); } -void Webserver::SetPassword(const char* pw) -{ - // Users sometimes put a tab character between the password and the comment, so allow for this - CopyParameterText(pw, password, ARRAY_SIZE(password)); -} - -void Webserver::SetName(const char* nm) -{ - // Users sometimes put a tab character between the machine name and the comment, so allow for this - CopyParameterText(nm, myName, ARRAY_SIZE(myName)); -} - -// Copy some parameter text, stopping at the first control character or when the destination buffer is full, and removing trailing spaces -void Webserver::CopyParameterText(const char* src, char *dst, size_t length) -{ - size_t i; - for (i = 0; i + 1 < length && src[i] >= ' '; ++i) - { - dst[i] = src[i]; - } - // Remove any trailing spaces - while (i > 0 && dst[i - 1] == ' ') - { - --i; - } - dst[i] = 0; -} - -const char *Webserver::GetName() const -{ - return myName; -} - -bool Webserver::CheckPassword(const char *pw) const -{ - return StringEquals(pw, password); -} - // Get the actual amount of gcode buffer space we have unsigned int Webserver::GetGcodeBufferSpace() const { @@ -333,32 +300,27 @@ void Webserver::ProcessGcode(const char* gc) FileStore *configFile = platform->GetFileStore(platform->GetSysDir(), platform->GetConfigFile(), false); if (configFile == NULL) { - MessageStringToWebInterface("Configuration file not found", true); + ResponseToWebInterface("Configuration file not found", true); } else { + reprap.MessageToGCodeReply(""); + char c; - size_t i = 0; bool reading_whitespace = false; - while (i < gcodeReply.Length() - 1 && configFile->Read(c)) + while (configFile->Read(c)) { if (!reading_whitespace || (c != ' ' && c != '\t')) { - gcodeReply[i++] = c; + reprap.AppendCharToStatusResponse(c); } reading_whitespace = (c == ' ' || c == '\t'); } configFile->Close(); - gcodeReply[i] = 0; - ++seq; - telnetInterpreter->HandleGcodeReply(gcodeReply.Pointer()); + telnetInterpreter->HandleGcodeReply(reprap.GetGcodeReply().Pointer()); } } - else if (StringStartsWith(gc, "M25") && !isDigit(gc[3])) // pause SD card print - { - reprap.GetGCodes()->PauseSDPrint(); - } else { StoreGcodeData(gc, strlen(gc) + 1); @@ -389,7 +351,7 @@ char Webserver::ReadGCode() // Process a received string of gcodes void Webserver::LoadGcodeBuffer(const char* gc) { - char gcodeTempBuf[GCODE_LENGTH]; + char gcodeTempBuf[GcodeLength]; uint16_t gtp = 0; bool inComment = false; for (;;) @@ -442,8 +404,7 @@ void Webserver::StoreGcodeData(const char* data, size_t len) { if (len > GetGcodeBufferSpace()) { - platform->Message(HOST_MESSAGE, "Webserver: GCode buffer overflow.\n"); - MessageStringToWebInterface("Webserver: GCode buffer overflow", true); + platform->Message(BOTH_ERROR_MESSAGE, "GCode buffer overflow in Webserver!\n"); } else { @@ -464,8 +425,9 @@ void Webserver::StoreGcodeData(const char* data, size_t len) // Handle immediate disconnects here (cs will be freed after this call) void Webserver::ConnectionLost(const ConnectionState *cs) { - // Inform protocol handlers that this connection has been lost + // Inform protcol handlers that this connection has been lost uint16_t local_port = cs->GetLocalPort(); + uint16_t data_port = network->GetDataPort(); ProtocolInterpreter *interpreter; switch (local_port) { @@ -482,15 +444,19 @@ void Webserver::ConnectionLost(const ConnectionState *cs) break; default: /* FTP data */ - interpreter = ftpInterpreter; - break; - } + if (local_port == data_port) + { + interpreter = ftpInterpreter; + break; + } - if (interpreter->DebugEnabled()) + platform->Message(BOTH_ERROR_MESSAGE, "Webserver: Connection closed at local port %d, but no handler found!\n", local_port); + return; + } + if (reprap.Debug(moduleWebserver)) { - debugPrintf("Webserver: ConnectionLost called with port %d\n", local_port); + platform->Message(HOST_MESSAGE, "Webserver: ConnectionLost called with port %d\n", local_port); } - interpreter->ConnectionLost(local_port); // If our reading connection is lost, it will be no longer important which connection is read from first. @@ -500,7 +466,7 @@ void Webserver::ConnectionLost(const ConnectionState *cs) } } -void Webserver::MessageStringToWebInterface(const char *s, bool error) +void Webserver::ResponseToWebInterface(const char *s, bool error) { if (!webserverActive) { @@ -509,47 +475,46 @@ void Webserver::MessageStringToWebInterface(const char *s, bool error) if (strlen(s) == 0 && !error) { - gcodeReply.copy("ok"); - telnetInterpreter->HandleGcodeReply("ok"); + reprap.MessageToGCodeReply(s); + telnetInterpreter->HandleGcodeReply("ok\r\n"); } else { if (error) { - gcodeReply.printf("Error: %s", s); - telnetInterpreter->HandleGcodeReply("Error: ", true); + reprap.MessageToGCodeReply("Error: "); + reprap.AppendMessageToGCodeReply(s); + + telnetInterpreter->HandleGcodeReply("Error: "); telnetInterpreter->HandleGcodeReply(s); } else { - gcodeReply.copy(s); + reprap.MessageToGCodeReply(s); telnetInterpreter->HandleGcodeReply(s); } } - - ++seq; } -void Webserver::AppendReplyToWebInterface(const char *s, bool error) +void Webserver::AppendResponseToWebInterface(const char *s) { if (!webserverActive) { return; } - gcodeReply.cat(s); - ++seq; - telnetInterpreter->HandleGcodeReply(s, true); + reprap.AppendMessageToGCodeReply(s); + telnetInterpreter->HandleGcodeReply(s); } - //******************************************************************************************** // //********************** Generic Procotol Interpreter implementation ************************* // //******************************************************************************************** -ProtocolInterpreter::ProtocolInterpreter(Platform *p, Webserver *ws) : platform(p), webserver(ws) +ProtocolInterpreter::ProtocolInterpreter(Platform *p, Webserver *ws, Network *n) + : platform(p), webserver(ws), network(n) { uploadState = notUploading; uploadPointer = NULL; @@ -661,7 +626,7 @@ void ProtocolInterpreter::FinishUpload(uint32_t file_length) } // Check the file length is as expected - if (uploadState == uploadOK && file_length != 0 && fileBeingUploaded.Length() != file_length + numContinuationBytes) + if (uploadState == uploadOK && file_length != 0 && fileBeingUploaded.Length() + numContinuationBytes != file_length) { uploadState = uploadError; platform->Message(HOST_MESSAGE, "Uploaded file size is different!\n"); @@ -682,11 +647,7 @@ void ProtocolInterpreter::FinishUpload(uint32_t file_length) filenameBeingUploaded[0] = 0; } -// This is overridden in class HttpInterpreter -bool ProtocolInterpreter::DebugEnabled() const -{ - return reprap.Debug(moduleWebserver); -} + //******************************************************************************************** // @@ -696,8 +657,8 @@ bool ProtocolInterpreter::DebugEnabled() const -Webserver::HttpInterpreter::HttpInterpreter(Platform *p, Webserver *ws) - : ProtocolInterpreter(p, ws), state(doingCommandWord) +Webserver::HttpInterpreter::HttpInterpreter(Platform *p, Webserver *ws, Network *n) + : ProtocolInterpreter(p, ws, n), state(doingCommandWord) { } @@ -722,8 +683,7 @@ void Webserver::HttpInterpreter::SendFile(const char* nameOfFileToSend) } } - Network *net = reprap.GetNetwork(); - NetworkTransaction *req = net->GetTransaction(); + NetworkTransaction *req = network->GetTransaction(); req->Write("HTTP/1.1 200 OK\n"); const char* contentType; @@ -766,13 +726,29 @@ void Webserver::HttpInterpreter::SendFile(const char* nameOfFileToSend) } req->Write("Connection: close\n\n"); - net->SendAndClose(fileToSend); + network->SendAndClose(fileToSend); +} + +void Webserver::HttpInterpreter::SendGCodeReply() +{ + NetworkTransaction *req = network->GetTransaction(); + req->Write("HTTP/1.1 200 OK\n"); + req->Write("Content-Type: text/plain\n"); + req->Printf("Content-Length: %u\n", reprap.GetGcodeReply().strlen()); + req->Write("Connection: close\n\n"); + req->Write(reprap.GetGcodeReply()); + network->SendAndClose(NULL); } void Webserver::HttpInterpreter::SendJsonResponse(const char* command) { - Network *net = reprap.GetNetwork(); - NetworkTransaction *req = net->GetTransaction(); + if (IsAuthenticated() && StringEquals(command, "reply")) + { + SendGCodeReply(); + return; + } + + NetworkTransaction *req = network->GetTransaction(); bool keepOpen = false; bool mayKeepOpen; bool found; @@ -819,7 +795,8 @@ void Webserver::HttpInterpreter::SendJsonResponse(const char* command) req->Printf("Content-Length: %u\n", jsonResponse.strlen()); req->Printf("Connection: %s\n\n", keepOpen ? "keep-alive" : "close"); req->Write(jsonResponse); - net->SendAndClose(NULL, keepOpen); + + network->SendAndClose(NULL, keepOpen); } //---------------------------------------------------------------------------------------------------- @@ -830,89 +807,144 @@ void Webserver::HttpInterpreter::SendJsonResponse(const char* command) // 'value' is null-terminated, but we also pass its length in case it contains embedded nulls, which matter when uploading files. bool Webserver::HttpInterpreter::GetJsonResponse(const char* request, StringRef& response, const char* key, const char* value, size_t valueLength, bool& keepOpen) { - bool found = true; // assume success keepOpen = false; // assume we don't want to persist the connection + bool found = true; // assume success - if (StringEquals(request, "status")) // new style status request + if (StringEquals(request, "connect") && StringEquals(key, "password")) { - reprap.GetStatusResponse(response, 1); - } - else if (StringEquals(request, "poll")) // old style status request - { - reprap.GetStatusResponse(response, 0); - } - else if (StringEquals(request, "gcode") && StringEquals(key, "gcode")) - { - webserver->LoadGcodeBuffer(value); - response.printf("{\"buff\":%u}", webserver->GetGcodeBufferSpace()); + if (IsAuthenticated()) + { + // We're already authenticated, no need to check the password again + response.copy("{\"err\":0}"); + } + else if (reprap.CheckPassword(value)) + { + if (Authenticate()) + { + // This is only possible if we have an HTTP session left + response.copy("{\"err\":0}"); + } + else + { + // Otherwise report an error + response.copy("{\"err\":2}"); + } + } + else + { + // Wrong password + response.copy("{\"err\":1}"); + } } - else if (StringEquals(request, "upload_begin") && StringEquals(key, "name")) + else if (!IsAuthenticated()) { - FileStore *file = platform->GetFileStore("0:/", value, true); - StartUpload(file); - GetJsonUploadResponse(response); + // Don't respond if this IP is not authenticated + found = false; } - else if (StringEquals(request, "upload_data") && StringEquals(key, "data")) + else { - StoreUploadData(value, valueLength); + UpdateAuthentication(); - GetJsonUploadResponse(response); - keepOpen = true; - } - else if (StringEquals(request, "upload_end") && StringEquals(key, "size")) - { - uint32_t file_length = strtoul(value, NULL, 10); - FinishUpload(file_length); + if (StringEquals(request, "disconnect")) + { + RemoveAuthentication(); + response.copy("{\"err\":0}"); + } + else if (StringEquals(request, "status")) + { + int type = 0; + if (StringEquals(key, "type")) + { + type = atoi(value); + if (type < 1 || type > 3) + { + type = 1; + } - GetJsonUploadResponse(response); - } - else if (StringEquals(request, "upload_cancel")) - { - CancelUpload(); - response.copy("{\"err\":0}"); - } - else if (StringEquals(request, "delete") && StringEquals(key, "name")) - { - bool ok = platform->GetMassStorage()->Delete("0:/", value); - response.printf("{\"err\":%d}", (ok) ? 0 : 1); - } - else if (StringEquals(request, "files")) - { - const char* dir = (StringEquals(key, "dir")) ? value : platform->GetGCodeDir(); - reprap.GetFilesResponse(response, dir); - } - else if (StringEquals(request, "fileinfo")) - { - reprap.GetFileInfoResponse(response, (StringEquals(key, "name")) ? value : NULL); - } - else if (StringEquals(request, "name")) - { - reprap.GetNameResponse(response); - } - else if (StringEquals(request, "password") && StringEquals(key, "password")) - { - gotPassword = webserver->CheckPassword(value); - response.printf("{\"password\":\"%s\"}", (gotPassword) ? "right" : "wrong"); - } - else if (StringEquals(request, "axes")) - { - response.copy("{\"axes\":"); - char ch = '['; - for (int8_t drive = 0; drive < AXES; drive++) + reprap.GetStatusResponse(response, type, true); + } + else + { + // Deprecated + reprap.GetLegacyStatusResponse(response, 1, 0); + } + } + else if (StringEquals(request, "gcode") && StringEquals(key, "gcode")) { - response.catf("%c%.1f", ch, platform->AxisTotalLength(drive)); - ch = ','; + webserver->LoadGcodeBuffer(value); + response.printf("{\"buff\":%u}", webserver->GetGcodeBufferSpace()); + } + else if (StringEquals(request, "upload_begin") && StringEquals(key, "name")) + { + FileStore *file = platform->GetFileStore("0:/", value, true); + if (StartUpload(file)) + { + strncpy(filenameBeingUploaded, value, FILENAME_LENGTH); + filenameBeingUploaded[FILENAME_LENGTH - 1] = 0; + } + + GetJsonUploadResponse(response); + } + else if (StringEquals(request, "upload_data") && StringEquals(key, "data")) + { + StoreUploadData(value, valueLength); + + GetJsonUploadResponse(response); + keepOpen = true; + } + else if (StringEquals(request, "upload_end") && StringEquals(key, "size")) + { + uint32_t file_length = strtoul(value, NULL, 10); + FinishUpload(file_length); + + GetJsonUploadResponse(response); + } + else if (StringEquals(request, "upload_cancel")) + { + CancelUpload(); + response.copy("{\"err\":0}"); + } + else if (StringEquals(request, "delete") && StringEquals(key, "name")) + { + bool ok = platform->GetMassStorage()->Delete("0:/", value); + response.printf("{\"err\":%d}", (ok) ? 0 : 1); + } + else if (StringEquals(request, "files")) + { + // TODO: get rid of GetFilesResponse and write directly to NetworkTransaction! + const char* dir = (StringEquals(key, "dir")) ? value : platform->GetGCodeDir(); + reprap.GetFilesResponse(response, dir); + } + else if (StringEquals(request, "fileinfo")) + { + reprap.GetFileInfoResponse(response, (StringEquals(key, "name")) ? value : NULL); + } + else if (StringEquals(request, "name")) + { + reprap.GetNameResponse(response); + } + else if (StringEquals(request, "connect")) + { + CancelUpload(); + reprap.GetStatusResponse(response, 1, -1); + } + else if (StringEquals(request, "mkdir") && StringEquals(key, "dir")) + { + bool ok = (platform->GetMassStorage()->MakeDirectory(value)); + response.printf("{\"err\":%d}", (ok) ? 0 : 1); + } + else if (StringEquals(request, "config")) + { + if (StringEquals(key, "type")) + { + int type = max<int>(2, min<int>(0, atoi(value))); + // TODO: implement this + } + } + else + { + found = false; } - response.cat("]}"); - } - else if (StringEquals(request, "connect")) - { - CancelUpload(); - reprap.GetStatusResponse(response, 1); - } - else - { - found = false; } return found; @@ -933,6 +965,10 @@ void Webserver::HttpInterpreter::ResetState() commandWords[0] = clientMessage; } +void Webserver::HttpInterpreter::ResetSessions() +{ + numActiveSessions = 0; +} // Process a character from the client // Rewritten as a state machine by dc42 to increase capability and speed, and reduce RAM requirement. @@ -1243,7 +1279,7 @@ bool Webserver::HttpInterpreter::CharFromClient(char c) // Return true if the message is complete, false if we want to continue receiving data (i.e. postdata) bool Webserver::HttpInterpreter::ProcessMessage() { - if(reprap.Debug(moduleWebserver)) + if (reprap.Debug(moduleWebserver)) { platform->Message(HOST_MESSAGE, "HTTP request:"); for (unsigned int i = 0; i < numCommandWords; ++i) @@ -1290,16 +1326,96 @@ bool Webserver::HttpInterpreter::RejectMessage(const char* response, unsigned in { platform->Message(HOST_MESSAGE, "Webserver: rejecting message with: %s\n", response); - Network *net = reprap.GetNetwork(); - NetworkTransaction *req = net->GetTransaction(); + NetworkTransaction *req = network->GetTransaction(); req->Printf("HTTP/1.1 %u %s\nConnection: close\n\n", code, response); - net->SendAndClose(NULL); + network->SendAndClose(NULL); ResetState(); return true; } +// Authenticate current IP and return true on success +bool Webserver::HttpInterpreter::Authenticate() +{ + if (numActiveSessions < maxSessions) + { + sessionIP[numActiveSessions] = network->GetTransaction()->GetRemoteIP(); + sessionLastQueryTime[numActiveSessions] = platform->Time(); + numActiveSessions++; + return true; + } + return false; +} + +bool Webserver::HttpInterpreter::IsAuthenticated() const +{ + if (reprap.NoPasswordSet()) + { + // Make password authentication optional if there is no explicit password set + return true; + } + + unsigned int ip = network->GetTransaction()->GetRemoteIP(); + for(uint8_t i=0; i<numActiveSessions; i++) + { + if (sessionIP[i] == ip) + { + return true; + } + } + + return false; +} + +void Webserver::HttpInterpreter::UpdateAuthentication() +{ + unsigned int ip = network->GetTransaction()->GetRemoteIP(); + for(int i=numActiveSessions - 1; i>=0; i--) + { + if (sessionIP[i] == ip) + { + sessionLastQueryTime[i] = platform->Time(); + break; + } + } +} + +void Webserver::HttpInterpreter::RemoveAuthentication() +{ + unsigned int ip = network->GetTransaction()->GetRemoteIP(); + for(int i=numActiveSessions - 1; i>=0; i--) + { + if (sessionIP[i] == ip) + { + for(int k=numActiveSessions - 1; k > i; k--) + { + sessionIP[k - 1] = sessionIP[k]; + sessionLastQueryTime[k - 1] = sessionLastQueryTime[k]; + } + numActiveSessions--; + break; + } + } +} + +void Webserver::HttpInterpreter::CheckSessions() +{ + const float time = platform->Time(); + for(int i=numActiveSessions - 1; i>=0; i--) + { + if (time - sessionLastQueryTime[i] > httpSessionTimeout) + { + for(int k=numActiveSessions - 1; k > i; k--) + { + sessionIP[k - 1] = sessionIP[k]; + sessionLastQueryTime[k - 1] = sessionLastQueryTime[k]; + } + numActiveSessions--; + } + } +} + //******************************************************************************************** // @@ -1307,32 +1423,31 @@ bool Webserver::HttpInterpreter::RejectMessage(const char* response, unsigned in // //******************************************************************************************** -Webserver::FtpInterpreter::FtpInterpreter(Platform *p, Webserver *ws) - : ProtocolInterpreter(p, ws), state(authenticating), clientPointer(0) +Webserver::FtpInterpreter::FtpInterpreter(Platform *p, Webserver *ws, Network *n) + : ProtocolInterpreter(p, ws, n), state(authenticating), clientPointer(0) { strcpy(currentDir, "/"); } void Webserver::FtpInterpreter::ConnectionEstablished() { - if (DebugEnabled()) + if (reprap.Debug(moduleWebserver)) { - platform->Message(DEBUG_MESSAGE, "Webserver: FTP connection established!\n"); + platform->Message(HOST_MESSAGE, "Webserver: FTP connection established!\n"); } - Network *net = reprap.GetNetwork(); - NetworkTransaction *req = net->GetTransaction(); + NetworkTransaction *req = network->GetTransaction(); switch (state) { case waitingForPasvPort: if (req->GetLocalPort() == 21) { - net->SendAndClose(NULL); + network->SendAndClose(NULL); return; } - net->SaveDataConnection(); + network->SaveDataConnection(); state = pasvPortConnected; break; @@ -1343,7 +1458,7 @@ void Webserver::FtpInterpreter::ConnectionEstablished() if (req->GetLocalPort() == 21) { req->Write("220 RepRapPro Ormerod\r\n"); - net->SendAndClose(NULL, true); + network->SendAndClose(NULL, true); ResetState(); } @@ -1357,11 +1472,10 @@ void Webserver::FtpInterpreter::ConnectionLost(uint16_t local_port) if (local_port != 21) { // Close the data port - Network *net = reprap.GetNetwork(); - net->CloseDataPort(); + network->CloseDataPort(); // Send response - if (net->AcquireFTPTransaction()) + if (network->AcquireFTPTransaction()) { if (state == doingPasvIO) { @@ -1408,9 +1522,9 @@ bool Webserver::FtpInterpreter::CharFromClient(char c) case '\n': clientMessage[clientPointer++] = 0; - if (DebugEnabled()) + if (reprap.Debug(moduleWebserver)) { - platform->Message(DEBUG_MESSAGE, "FtpInterpreter::ProcessLine called with state %d:\n%s\n", state, clientMessage); + platform->Message(HOST_MESSAGE, "FtpInterpreter::ProcessLine called with state %d:\n%s\n", state, clientMessage); } if (clientPointer > 1) // only process a new line if we actually received data @@ -1420,9 +1534,9 @@ bool Webserver::FtpInterpreter::CharFromClient(char c) return true; } - if (DebugEnabled()) + if (reprap.Debug(moduleWebserver)) { - platform->Message(DEBUG_MESSAGE, "FtpInterpreter::ProcessLine call finished.\n"); + platform->Message(HOST_MESSAGE, "FtpInterpreter::ProcessLine call finished.\n"); } clientPointer = 0; @@ -1441,19 +1555,27 @@ void Webserver::FtpInterpreter::ResetState() clientPointer = 0; strcpy(currentDir, "/"); - Network *net = reprap.GetNetwork(); - net->CloseDataPort(); - + network->CloseDataPort(); CancelUpload(); state = authenticating; } +bool Webserver::FtpInterpreter::StoreUploadData(const char* data, unsigned int len) +{ + if (uploadState == uploadOK) + { + uploadPointer = data; + uploadLength = len; + return true; + } + return false; +} + + // return true if an error has occurred, false otherwise void Webserver::FtpInterpreter::ProcessLine() { - Network *net = reprap.GetNetwork(); - switch (state) { case authenticating: @@ -1478,7 +1600,7 @@ void Webserver::FtpInterpreter::ProcessLine() } pass[pass_length] = 0; - if (webserver->CheckPassword(pass)) + if (reprap.CheckPassword(pass)) { state = authenticated; SendReply(230, "Login successful."); @@ -1488,10 +1610,10 @@ void Webserver::FtpInterpreter::ProcessLine() SendReply(530, "Login incorrect.", false); } } - // if this is different, disconnect immediately + // if it's different, send response 500 to indicate we don't know the code (might be AUTH or so) else { - SendReply(500, "Unknown login command.", false); + SendReply(500, "Unknown login command."); } break; @@ -1548,12 +1670,12 @@ void Webserver::FtpInterpreter::ProcessLine() else if (StringEquals(clientMessage, "PASV")) { /* get local IP address */ - const byte *ip_address = reprap.GetPlatform()->IPAddress(); + const byte *ip_address = platform->IPAddress(); - /* open random port > 1024 */ + /* open random port > 1023 */ rand(); uint16_t pasv_port = random(1024, 65535); - net->OpenDataPort(pasv_port); + network->OpenDataPort(pasv_port); portOpenTime = platform->Time(); state = waitingForPasvPort; @@ -1642,16 +1764,16 @@ void Webserver::FtpInterpreter::ProcessLine() } else if (StringStartsWith(clientMessage, "RNTO")) { - char buffer[MaxFilenameLength]; - strncpy(buffer, filename, MaxFilenameLength); + char buffer[FILENAME_LENGTH]; + strncpy(buffer, filename, FILENAME_LENGTH); ReadFilename(4); if (buffer[0] != '/' && filename[0] != '/') { - char old_filename[MaxFilenameLength]; + char old_filename[FILENAME_LENGTH]; const char *new_filename; - strncpy(old_filename, platform->GetMassStorage()->CombineName(currentDir, buffer), MaxFilenameLength); + strncpy(old_filename, platform->GetMassStorage()->CombineName(currentDir, buffer), FILENAME_LENGTH); new_filename = platform->GetMassStorage()->CombineName(currentDir, filename); if (platform->GetMassStorage()->Rename(old_filename, new_filename)) @@ -1699,40 +1821,40 @@ void Webserver::FtpInterpreter::ProcessLine() break; case waitingForPasvPort: - if (!DebugEnabled() && platform->Time() - portOpenTime > pasvPortTimeout) + if (!reprap.Debug(moduleWebserver) && platform->Time() - portOpenTime > pasvPortTimeout) { SendReply(425, "Failed to establish connection."); - net->CloseDataPort(); + network->CloseDataPort(); state = authenticated; } else { - net->RepeatTransaction(); + network->WaitForDataConection(); } break; case pasvPortConnected: // save current connection state so we can send '226 Transfer complete.' when ConnectionLost() is called - net->SaveFTPConnection(); + network->SaveFTPConnection(); // list directory entries if (StringEquals(clientMessage, "LIST")) { // send response via main port strncpy(ftpResponse, "150 Here comes the directory listing.\r\n", ftpResponseLength); - NetworkTransaction *ftp_req = net->GetTransaction(); + NetworkTransaction *ftp_req = network->GetTransaction(); ftp_req->Write(ftpResponse); - net->SendAndClose(NULL, true); + network->SendAndClose(NULL, true); // send file list via data port - if (net->AcquireDataTransaction()) + if (network->AcquireDataTransaction()) { FileInfo file_info; if (platform->GetMassStorage()->FindFirst(currentDir, file_info)) { - NetworkTransaction *data_req = net->GetTransaction(); + NetworkTransaction *data_req = network->GetTransaction(); char line[300]; do { @@ -1747,13 +1869,14 @@ void Webserver::FtpInterpreter::ProcessLine() data_req->Write(line); } while (platform->GetMassStorage()->FindNext(file_info)); } - net->SendAndClose(NULL); + + network->SendAndClose(NULL); state = doingPasvIO; } else { SendReply(500, "Unknown error."); - net->CloseDataPort(); + network->CloseDataPort(); state = authenticated; } } @@ -1774,13 +1897,16 @@ void Webserver::FtpInterpreter::ProcessLine() if (StartUpload(file)) { + strncpy(filenameBeingUploaded, filename, FILENAME_LENGTH); + filenameBeingUploaded[FILENAME_LENGTH - 1] = 0; + SendReply(150, "OK to send data."); state = doingPasvIO; } else { SendReply(550, "Failed to open file."); - net->CloseDataPort(); + network->CloseDataPort(); state = authenticated; } } @@ -1808,16 +1934,16 @@ void Webserver::FtpInterpreter::ProcessLine() snprintf(ftpResponse, ftpResponseLength, "Opening data connection for %s (%lu bytes).", filename, fs->Length()); SendReply(150, ftpResponse); - if (net->AcquireDataTransaction()) + if (network->AcquireDataTransaction()) { // send the file via data port - net->SendAndClose(fs, false); + network->SendAndClose(fs, false); state = doingPasvIO; } else { SendReply(500, "Unknown error."); - net->CloseDataPort(); + network->CloseDataPort(); state = authenticated; } } @@ -1826,7 +1952,7 @@ void Webserver::FtpInterpreter::ProcessLine() else { SendReply(500, "Unknown command."); - net->CloseDataPort(); + network->CloseDataPort(); state = authenticated; } @@ -1843,7 +1969,7 @@ void Webserver::FtpInterpreter::ProcessLine() } else { - net->CloseDataPort(); + network->CloseDataPort(); SendReply(226, "ABOR successful."); } } @@ -1851,7 +1977,7 @@ void Webserver::FtpInterpreter::ProcessLine() else { SendReply(500, "Unknown command."); - net->CloseDataPort(); + network->CloseDataPort(); state = authenticated; } @@ -1861,27 +1987,25 @@ void Webserver::FtpInterpreter::ProcessLine() void Webserver::FtpInterpreter::SendReply(int code, const char *message, bool keepConnection) { - Network *net = reprap.GetNetwork(); - NetworkTransaction *req = net->GetTransaction(); + NetworkTransaction *req = network->GetTransaction(); req->Printf("%d %s\r\n", code, message); - net->SendAndClose(NULL, keepConnection); + network->SendAndClose(NULL, keepConnection); } void Webserver::FtpInterpreter::SendFeatures() { - Network *net = reprap.GetNetwork(); - NetworkTransaction *req = net->GetTransaction(); + NetworkTransaction *req = network->GetTransaction(); req->Write("211-Features:\r\n"); req->Write("PASV\r\n"); // support PASV mode req->Write("211 End\r\n"); - net->SendAndClose(NULL, true); + network->SendAndClose(NULL, true); } void Webserver::FtpInterpreter::ReadFilename(int start) { int filenameLength = 0; bool readingPath = false; - for(int i=start; i<clientPointer && i<MaxFilenameLength + start -1; i++) + for(int i=start; i<clientPointer && filenameLength<FILENAME_LENGTH; i++) { switch (clientMessage[i]) { @@ -1911,14 +2035,14 @@ void Webserver::FtpInterpreter::ReadFilename(int start) void Webserver::FtpInterpreter::ChangeDirectory(const char *newDirectory) { - char combinedPath[MaxFilenameLength]; + char combinedPath[FILENAME_LENGTH]; if (newDirectory[0] != 0) { /* Prepare the new directory path */ if (newDirectory[0] == '/') // absolute path { - strncpy(combinedPath, newDirectory, MaxFilenameLength); + strncpy(combinedPath, newDirectory, FILENAME_LENGTH); } else // relative path { @@ -1932,7 +2056,7 @@ void Webserver::FtpInterpreter::ChangeDirectory(const char *newDirectory) } else { - strncpy(combinedPath, currentDir, MaxFilenameLength); + strncpy(combinedPath, currentDir, FILENAME_LENGTH); for(int i=strlen(combinedPath) -2; i>=0; i--) { if (combinedPath[i] == '/') @@ -1945,12 +2069,12 @@ void Webserver::FtpInterpreter::ChangeDirectory(const char *newDirectory) } else // go to child directory { - strncpy(combinedPath, currentDir, MaxFilenameLength); + strncpy(combinedPath, currentDir, FILENAME_LENGTH); if (strlen(currentDir) > 1) { - strncat(combinedPath, "/", MaxFilenameLength - strlen(combinedPath) - 1); + strncat(combinedPath, "/", FILENAME_LENGTH - strlen(combinedPath) - 1); } - strncat(combinedPath, newDirectory, MaxFilenameLength - strlen(combinedPath) - 1); + strncat(combinedPath, newDirectory, FILENAME_LENGTH - strlen(combinedPath) - 1); } } @@ -1963,7 +2087,7 @@ void Webserver::FtpInterpreter::ChangeDirectory(const char *newDirectory) /* Verify path and change it */ if (platform->GetMassStorage()->PathExists(combinedPath)) { - strncpy(currentDir, combinedPath, MaxFilenameLength); + strncpy(currentDir, combinedPath, FILENAME_LENGTH); SendReply(250, "Directory successfully changed."); } else @@ -1984,19 +2108,19 @@ void Webserver::FtpInterpreter::ChangeDirectory(const char *newDirectory) // //******************************************************************************************** -Webserver::TelnetInterpreter::TelnetInterpreter(Platform *p, Webserver *ws) : ProtocolInterpreter(p, ws) +Webserver::TelnetInterpreter::TelnetInterpreter(Platform *p, Webserver *ws, Network *n) + : ProtocolInterpreter(p, ws, n) { ResetState(); } void Webserver::TelnetInterpreter::ConnectionEstablished() { - Network *net = reprap.GetNetwork(); - NetworkTransaction *req = net->GetTransaction(); + NetworkTransaction *req = network->GetTransaction(); req->Write("RepRapPro Ormerod Telnet Interface\r\n\r\n"); req->Write("Please enter your password:\r\n"); req->Write("> "); - net->SendAndClose(NULL, true); + network->SendAndClose(NULL, true); } void Webserver::TelnetInterpreter::ConnectionLost(uint16_t local_port) @@ -2050,28 +2174,28 @@ void Webserver::TelnetInterpreter::ResetState() { state = authenticating; clientPointer = 0; + sendPending = false; } void Webserver::TelnetInterpreter::ProcessLine() { - Network *net = reprap.GetNetwork(); - NetworkTransaction *req = net->GetTransaction(); + NetworkTransaction *req = network->GetTransaction(); switch (state) { case authenticating: - if (webserver->CheckPassword(clientMessage)) + if (reprap.CheckPassword(clientMessage)) { - net->SaveTelnetConnection(); + network->SaveTelnetConnection(); state = authenticated; req->Write("Log in successful!\r\n"); - net->SendAndClose(NULL, true); + network->SendAndClose(NULL, true); } else { req->Write("Invalid password.\r\n> "); - net->SendAndClose(NULL, true); + network->SendAndClose(NULL, true); } break; @@ -2080,49 +2204,58 @@ void Webserver::TelnetInterpreter::ProcessLine() if (StringEquals(clientMessage, "exit") || StringEquals(clientMessage, "quit")) { req->Write("Goodbye.\r\n"); - net->SendAndClose(NULL); + network->SendAndClose(NULL); } // All other commands are processed by the Webserver else { webserver->ProcessGcode(clientMessage); - net->CloseTransaction(); + if (sendPending) + { + sendPending = false; + network->SendAndClose(NULL, true); + } + else + { + network->CloseTransaction(); + } } break; } } -void Webserver::TelnetInterpreter::HandleGcodeReply(const char *reply, bool haveMore) +void Webserver::TelnetInterpreter::HandleGcodeReply(const char *reply) { - Network *net = reprap.GetNetwork(); - if (state >= authenticated && net->AcquireTelnetTransaction()) + if (state >= authenticated && network->AcquireTelnetTransaction()) { - NetworkTransaction *req = net->GetTransaction(); + NetworkTransaction *req = network->GetTransaction(); // Whenever a new line is read, we also need to send a carriage return - bool append_line = false; - while (reply[0] != 0) + while (*reply != 0) { - append_line = true; - if (reply[0] == '\n') + if (*reply == '\n') { req->Write('\r'); - append_line = false; } - req->Write(reply[0]); + req->Write(*reply); reply++; } - // Only append a line break if reply didn't contain one and if we aren't expecting any more data - if (append_line && !haveMore) - { - req->Write("\r\n"); - } - - net->SendAndClose(NULL, true); + // We must not send the message here, because then we'd have to deal with LWIP internals + sendPending = true; } } +bool Webserver::TelnetInterpreter::HasRemainingData() const +{ + return sendPending; +} + +void Webserver::TelnetInterpreter::RemainingDataSent() +{ + sendPending = false; +} + //******************************************************************************************** // @@ -2148,90 +2281,110 @@ bool Webserver::GetFileInfo(const char *directory, const char *fileName, GcodeFi const size_t readSize = 512; // read 512 bytes at a time (1K doesn't seem to work when we read from the end) const size_t overlap = 100; char buf[readSize + overlap + 1]; // need the +1 so we can add a null terminator + bool foundLayerHeight = false; unsigned int filamentsFound = 0, nFilaments; float filaments[DRIVES - AXES]; // Get slic3r settings by reading from the start of the file. We only read the first 2K or so, everything we are looking for should be there. - for (unsigned int i = 0; i < 4; ++i) + for(uint8_t i=0; i<4; i++) { size_t sizeToRead = (size_t)min<unsigned long>(info.fileSize, readSize + overlap); int nbytes = f->Read(buf, sizeToRead); - if (nbytes == (int)sizeToRead) + if (nbytes != (int)sizeToRead) + { + break; // read failed so give up + } + else { buf[sizeToRead] = 0; // Search for filament usage (Cura puts it at the beginning of a G-code file) - nFilaments = FindFilamentUsed(buf, sizeToRead, filaments, DRIVES - AXES); - if (nFilaments != 0 && nFilaments >= filamentsFound) + if (!filamentsFound) { - filamentsFound = min<unsigned int>(nFilaments, info.numFilaments); - for (unsigned int i = 0; i < filamentsFound; ++i) + nFilaments = FindFilamentUsed(buf, sizeToRead, filaments, DRIVES - AXES); + if (nFilaments != 0 && nFilaments >= filamentsFound) { - info.filamentNeeded[i] = filaments[i]; + filamentsFound = min<unsigned int>(nFilaments, info.numFilaments); + for (unsigned int i = 0; i < filamentsFound; ++i) + { + info.filamentNeeded[i] = filaments[i]; + } } } // Look for layer height - foundLayerHeight = FindLayerHeight(buf, sizeToRead, info.layerHeight); + if (!foundLayerHeight) + { + foundLayerHeight = FindLayerHeight(buf, sizeToRead, info.layerHeight); + } - // Look for slicer or Simplify3D generated-by comment program - const char* generatedByString = " generated by "; - const char* pos = strstr(buf, generatedByString); - size_t generatedByLength = ARRAY_SIZE(info.generatedBy); - if (pos != NULL) + // Look for slicer program + if (!info.generatedBy[0]) { - pos += strlen(generatedByString); - size_t i = 0; - while (i < ARRAY_SIZE(info.generatedBy) - 1 && *pos >= ' ') + // Slic3r and S3D + const char* generatedByString = "generated by "; + char* pos = strstr(buf, generatedByString); + size_t generatedByLength = ARRAY_SIZE(info.generatedBy); + if (pos != NULL) { - char c = *pos++; - if (c == '"' || c == '\\') + pos += strlen(generatedByString); + size_t i = 0; + while (i < ARRAY_SIZE(info.generatedBy) - 1 && *pos >= ' ') { - // Need to escape the quote-mark for JSON - if ( i > ARRAY_SIZE(info.generatedBy) - 3) + char c = *pos++; + if (c == '"' || c == '\\') { - break; + // Need to escape the quote-mark for JSON + if (i > ARRAY_SIZE(info.generatedBy) - 3) + { + break; + } + info.generatedBy[i++] = '\\'; } - info.generatedBy[i++] = '\\'; + info.generatedBy[i++] = c; } - info.generatedBy[i++] = c; + info.generatedBy[i] = 0; } - info.generatedBy[i] = 0; - } - // Look for Cura comment - const char* slicedAtString = ";Sliced at: "; - pos = strstr(buf, slicedAtString); - if (pos != NULL) - { - pos += strlen(slicedAtString); - strcpy(info.generatedBy, "Cura at "); - size_t i = 8; - while (i < ARRAY_SIZE(info.generatedBy) - 1 && *pos >= ' ') + // Cura + const char* slicedAtString = ";Sliced at: "; + pos = strstr(buf, slicedAtString); + if (pos != NULL) { - char c = *pos++; - if (c == '"' || c == '\\') + pos += strlen(slicedAtString); + strcpy(info.generatedBy, "Cura at "); + size_t i = 8; + while (i < ARRAY_SIZE(info.generatedBy) - 1 && *pos >= ' ') { - // Need to escape the quote-mark for JSON - if (i > ARRAY_SIZE(info.generatedBy) - 3) + char c = *pos++; + if (c == '"' || c == '\\') { - break; + // Need to escape the quote-mark for JSON + if (i > ARRAY_SIZE(info.generatedBy) - 3) + { + break; + } + info.generatedBy[i++] = '\\'; } - info.generatedBy[i++] = '\\'; + info.generatedBy[i++] = c; } - info.generatedBy[i++] = c; + info.generatedBy[i] = 0; } - info.generatedBy[i] = 0; } // Add code to look for other values here... } + + // Have we collected everything? + if (filamentsFound && foundLayerHeight && info.generatedBy[0]) + { + break; + } } // Now get the object height and filament used by reading the end of the file { - bool searchForFilaments = (filamentsFound == 0); size_t sizeToRead; if (info.fileSize <= readSize + overlap) { @@ -2258,10 +2411,9 @@ bool Webserver::GetFileInfo(const char *directory, const char *fileName, GcodeFi { break; // read failed so give up } - buf[sizeToScan] = 0; // add a null terminator // Search for filament used - if (searchForFilaments) + if (!filamentsFound) { nFilaments = FindFilamentUsed(buf, sizeToScan, filaments, DRIVES - AXES); if (nFilaments != 0 && nFilaments >= filamentsFound) @@ -2285,6 +2437,7 @@ bool Webserver::GetFileInfo(const char *directory, const char *fileName, GcodeFi { break; // quit if found height } + if (seekPos == 0 || info.fileSize - seekPos >= 200000uL) // scan up to about the last 200K of the file (32K wasn't enough) { break; // quit if reached start of file or already scanned the last 32K of the file @@ -2304,42 +2457,70 @@ bool Webserver::GetFileInfo(const char *directory, const char *fileName, GcodeFi return false; } -// Scan the buffer for a G1 Zxxx command. The buffer is null-terminated. Simplify3D uses G0 Z instead. +// Scan the buffer for a G1 Zxxx command. The buffer is null-terminated. bool Webserver::FindHeight(const char* buf, size_t len, float& height) { //debugPrintf("Scanning %u bytes starting %.100s\n", len, buf); - if (len >= 5) // need to check this here to prevent arithmetic underflow later on + bool inComment; + unsigned int zPos; + for(size_t i = len - 5; i > 0; i--) { - size_t i = len - 5; - for(;;) + // Look for last "G0/G1 ... Z#HEIGHT#" command as generated by common slicers + if (buf[i] == 'G' && (buf[i + 1] == '0' || buf[i + 1] == '1') && buf[i + 2] == ' ') { - if (buf[i] == 'G' && (buf[i + 1] == '1' || buf[i + 1] == '0') && buf[i + 2] == ' ' && buf[i + 3] == 'Z' && isDigit(buf[i + 4])) + // Looks like we found a controlled move, however it could be in a comment, especially when using slic3r 1.1.1 + inComment = false; + size_t j = i; + while (j != 0) { - // Looks like we found a command to set the height, however it could be in a comment, especially when using slic3r 1.1.1 - size_t j = i; - while (j != 0) + --j; + char c = buf[j]; + if (c == '\n' || c == '\r') + { + // It's not in a comment + break; + } + if (c == ';') { - --j; - char c = buf[j]; - if (c == '\n' || c == '\r') + // It is in a comment, so give up on this one + inComment = true; + break; + } + } + if (inComment) + continue; + + // Find 'Z' position and grab that value + zPos = 0; + for(int j=i +3; j < len - 2; j++) + { + char c = buf[j]; + if (c < ' ') + { + // Skip all whitespaces... + while (j < len - 2 && c <= ' ') { -//debugPrintf("Found at offset %u text: %.100s\n", i, &buf[i + 4]); - // It's not in a comment - height = strtod(&buf[i + 4], NULL); - return true; + c = buf[++j]; } - if (c == ';') + // ...to make sure ";End" doesn't follow G0 .. Z#HEIGHT# + if (zPos != 0 && (buf[j] != ';' || buf[j + 1] != 'E')) { - // It is in a comment, so give up on this one - break; + //debugPrintf("Found at offset %u text: %.100s\n", zPos, &buf[zPos + 1]); + height = strtod(&buf[zPos + 1], NULL); + return true; } + break; + } + else if (c == ';') + { + // Ignore comments + break; + } + else if (c == 'Z') + { + zPos = j; } } - if (i == 0) - { - break; - } - --i; } } return false; @@ -2350,7 +2531,7 @@ bool Webserver::FindLayerHeight(const char *buf, size_t len, float& layerHeight) { // Look for layer_height as generated by Slic3r const char* layerHeightStringSlic3r = "; layer_height "; - const char *pos = strstr(buf, layerHeightStringSlic3r); + char *pos = strstr(buf, layerHeightStringSlic3r); if (pos != NULL) { pos += strlen(layerHeightStringSlic3r); @@ -2385,6 +2566,7 @@ bool Webserver::FindLayerHeight(const char *buf, size_t len, float& layerHeight) layerHeight = strtod(pos, NULL); return true; } + return false; } @@ -2395,9 +2577,9 @@ unsigned int Webserver::FindFilamentUsed(const char* buf, size_t len, float *fil unsigned int filamentsFound = 0; // Look for filament usage as generated by Slic3r and Cura - const char* filamentUsedStr = "ilament used"; // comment string used by slic3r, followed by filament used and "mm" + const char* filamentUsedStr = "ilament used"; // comment string used by slic3r and Cura, followed by filament used and "mm" const char* p = buf; - while (filamentsFound < maxFilaments && (p = strstr(p, filamentUsedStr)) != NULL) + while (filamentsFound < maxFilaments && (p = strstr(p, filamentUsedStr)) != NULL) { p += strlen(filamentUsedStr); while(strchr(" :=\t", *p) != NULL) @@ -2416,21 +2598,22 @@ unsigned int Webserver::FindFilamentUsed(const char* buf, size_t len, float *fil } } - if (filamentsFound == 0) + // Look for filament usage as generated by S3D + if (!filamentsFound) { - // Look for filament usage as generated by S3D - const char *filamentLengthStr = "ilament length"; // comment string used by S3D + const char *filamentLengthStr = "ilament length:"; // comment string used by S3D p = buf; while (filamentsFound < maxFilaments && (p = strstr(p, filamentLengthStr)) != NULL) { p += strlen(filamentLengthStr); while(strchr(" :=\t", *p) != NULL) { - ++p; + ++p; // this allows for " = " from default slic3r comment and ": " from default Cura comment } if (isDigit(*p)) { - filamentUsed[filamentsFound] = strtod(p, NULL); // S3D reports filament usage in mm, no conversion needed + char* q; + filamentUsed[filamentsFound] = strtod(p, &q); // S3D reports filament usage in mm, no conversion needed ++filamentsFound; } } @@ -2438,5 +2621,3 @@ unsigned int Webserver::FindFilamentUsed(const char* buf, size_t len, float *fil return filamentsFound; } - -// End diff --git a/Webserver.h b/Webserver.h index d44e915c..505016e1 100644 --- a/Webserver.h +++ b/Webserver.h @@ -30,8 +30,7 @@ Licence: GPL #ifndef WEBSERVER_H #define WEBSERVER_H -const unsigned int gcodeBufferLength = 512; // size of our gcode ring buffer, preferably a power of 2 -const unsigned int gcodeReplyBufferLength = 2048; // size of our gcode reply buffer +const unsigned int gcodeBufferLength = 512; // size of our gcode ring buffer, preferably a power of 2 /* HTTP */ @@ -39,18 +38,21 @@ const unsigned int gcodeReplyBufferLength = 2048; // size of our gcode reply buf #define KO_FIRST 3 const unsigned int webUploadBufferSize = 2300; // maximum size of HTTP upload packets (webMessageLength - 700) -const unsigned int webMessageLength = 3000; // maximum length of the web message we accept after decoding, excluding POST data +const unsigned int webMessageLength = 3000; // maximum length of the web message we accept after decoding const unsigned int maxCommandWords = 4; // max number of space-separated words in the command const unsigned int maxQualKeys = 5; // max number of key/value pairs in the qualifier const unsigned int maxHeaders = 10; // max number of key/value pairs in the headers -const unsigned int jsonReplyLength = 2000; // size of buffer used to hold JSON reply +const unsigned int jsonReplyLength = 1024; // size of buffer used to hold JSON reply + +const unsigned int maxSessions = 8; // maximum number of simultaneous HTTP sessions +const unsigned int httpSessionTimeout = 30; // HTTP session timeout in seconds /* FTP */ -const unsigned int ftpMessageLength = 256; // maximum line length for incoming FTP commands -const unsigned int ftpResponseLength = 256; // maximum FTP response length +const unsigned int ftpResponseLength = 128; // maximum FTP response length +const unsigned int ftpMessageLength = 128; // maximum line length for incoming FTP commands /* Telnet */ @@ -77,7 +79,7 @@ class ProtocolInterpreter { public: - ProtocolInterpreter(Platform *p, Webserver *ws); + ProtocolInterpreter(Platform *p, Webserver *ws, Network *n); virtual void ConnectionEstablished() { } virtual void ConnectionLost(uint16_t local_port) { } virtual bool CharFromClient(const char c) = 0; @@ -88,15 +90,13 @@ class ProtocolInterpreter void CancelUpload(); bool IsUploading() const { return uploadState != notUploading; } - virtual bool DebugEnabled() const; - virtual ~ProtocolInterpreter() { } // to keep Eclipse happy protected: - bool gotPassword; Platform *platform; Webserver *webserver; + Network *network; // Information for file uploading enum UploadState @@ -121,25 +121,18 @@ class Webserver { public: - Webserver(Platform* p); + Webserver(Platform* p, Network *n); void Init(); void Spin(); void Exit(); void Diagnostics(); - void SetPassword(const char* pw); - void SetName(const char* nm); - const char *GetName() const; - bool CheckPassword(const char* pw) const; - bool GCodeAvailable(); char ReadGCode(); + unsigned int GetGcodeBufferSpace() const; void ConnectionLost(const ConnectionState *cs); void ConnectionError(); - const StringRef& GetGcodeReply() const { return gcodeReply; } - unsigned int GetReplySeq() const { return seq; } - unsigned int GetGcodeBufferSpace() const; static bool GetFileInfo(const char *directory, const char *fileName, GcodeFileInfo& info); @@ -147,20 +140,20 @@ class Webserver protected: - void MessageStringToWebInterface(const char *s, bool error); - void AppendReplyToWebInterface(const char* s, bool error); - - private: + void ResponseToWebInterface(const char *s, bool error); + void AppendResponseToWebInterface(const char* s); class HttpInterpreter : public ProtocolInterpreter { public: - HttpInterpreter(Platform *p, Webserver *ws); - + HttpInterpreter(Platform *p, Webserver *ws, Network *n); bool CharFromClient(const char c); void ResetState(); + void ResetSessions(); + void CheckSessions(); + private: // HTTP server state enumeration. The order is important, in particular xxxEsc1 must follow xxx, and xxxEsc2 must follow xxxEsc1. @@ -190,27 +183,24 @@ class Webserver }; void SendFile(const char* nameOfFileToSend); + void SendGCodeReply(); void SendJsonResponse(const char* command); bool GetJsonResponse(const char* request, StringRef& response, const char* key, const char* value, size_t valueLength, bool& keepOpen); void GetJsonUploadResponse(StringRef& response); bool ProcessMessage(); bool RejectMessage(const char* s, unsigned int code = 500); - HttpState state; + bool Authenticate(); + bool IsAuthenticated() const; + void UpdateAuthentication(); + void RemoveAuthentication(); -// bool receivingPost; -// int boundaryCount; -// FileStore* postFile; -// bool postSeen; -// bool getSeen; -// bool clientLineIsBlank; + HttpState state; // Buffers for processing HTTP input char clientMessage[webMessageLength]; // holds the command, qualifier, and headers -// char postBoundary[postBoundaryLength]; // holds the POST boundary string -// char postFileName[postFilenameLength]; // holds the POST filename -// char postData[postDataLength]; // holds the POST data unsigned int clientPointer; // current index into clientMessage + char decodeChar; const char* commandWords[maxCommandWords]; KeyValueIndices qualifiers[maxQualKeys + 1]; // offsets into clientQualifier of the key/value pairs, the +1 is needed so that values can contain nulls @@ -219,8 +209,10 @@ class Webserver unsigned int numQualKeys; // number of qualifier keys we have found, <= maxQualKeys unsigned int numHeaderKeys; // number of keys we have found, <= maxHeaders - // Buffers to hold reply - char decodeChar; + // HTTP sessions + unsigned int numActiveSessions; + unsigned int sessionIP[maxSessions]; + float sessionLastQueryTime[maxSessions]; }; HttpInterpreter *httpInterpreter; @@ -228,12 +220,14 @@ class Webserver { public: - FtpInterpreter(Platform *p, Webserver *ws); + FtpInterpreter(Platform *p, Webserver *ws, Network *n); void ConnectionEstablished(); void ConnectionLost(uint16_t local_port); bool CharFromClient(const char c); void ResetState(); + bool StoreUploadData(const char* data, unsigned int len); + private: enum FtpState @@ -248,10 +242,10 @@ class Webserver char clientMessage[ftpMessageLength]; unsigned int clientPointer; - char ftpResponse[ftpResponseLength]; + char ftpResponse[ftpResponseLength]; // TODO: remove this - char currentDir[MaxFilenameLength]; char filename[MaxFilenameLength]; + char currentDir[MaxFilenameLength]; float portOpenTime; @@ -268,13 +262,15 @@ class Webserver { public: - TelnetInterpreter(Platform *p, Webserver *ws); + TelnetInterpreter(Platform *p, Webserver *ws, Network *n); void ConnectionEstablished(); void ConnectionLost(uint16_t local_port); bool CharFromClient(const char c); void ResetState(); - void HandleGcodeReply(const char* reply, bool haveMore = false); + void HandleGcodeReply(const char* reply); + bool HasRemainingData() const; + void RemainingDataSent(); private: @@ -287,6 +283,7 @@ class Webserver char clientMessage[telnetMessageLength]; unsigned int clientPointer; + bool sendPending; void ProcessLine(); }; @@ -300,21 +297,17 @@ class Webserver // File info methods static bool FindHeight(const char* buf, size_t len, float& height); static bool FindLayerHeight(const char* buf, size_t len, float& layerHeight); - static unsigned int FindFilamentUsed(const char* buf, size_t len, float *filamentUsed, unsigned int maxFilaments); - static void CopyParameterText(const char* src, char *dst, size_t length); + static unsigned int FindFilamentUsed(const char* buf, size_t len, float *filamentUsed, unsigned int maxFilaments); + + private: // Buffer to hold gcode that is ready for processing char gcodeBuffer[gcodeBufferLength]; unsigned int gcodeReadIndex, gcodeWriteIndex; // head and tail indices into gcodeBuffer - char gcodeReplyBuffer[gcodeReplyBufferLength]; - StringRef gcodeReply; - uint16_t seq; // reply sequence number, so that the client can tell if a json reply is new or not // Misc - char password[SHORT_STRING_LENGTH + 1]; - char myName[SHORT_STRING_LENGTH + 1]; - Platform* platform; + Network* network; bool webserverActive; const ConnectionState *readingConnection; |