Welcome to mirror list, hosted at ThFree Co, Russian Federation.

github.com/Duet3D/RepRapFirmware.git - Unnamed repository; edit this file 'description' to name the repository.
summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorDavid Crocker <dcrocker@eschertech.com>2016-05-27 22:59:44 +0300
committerDavid Crocker <dcrocker@eschertech.com>2016-05-27 22:59:44 +0300
commiteb5445770b0c7155fd8d7b3d86c0ac54e66d0499 (patch)
tree1e5a420b4237b46360aa0d40ca78045e9cd72efa
parent59d92525da4733d22d0b2ad9b06e64b898b24e1e (diff)
Version 1.13 beta 1
Added support for M581 and M582 commands M25 pause command can now be used inside a macro file to pause a file being printed from SD card Firmware update messages are now sent to USB and PanelDue (but the existing PanelDue firmware doesn't display them) Added gcode queue underrun counter, displayed in M122 Move diagnostic info M122 responses are now sent only to the comms channel that requested them Added support for additional firmware modules to be updated for Duet NG Corrected a possible problem with multiple incompatible gcodes being executed concurrently Support H parameter on M0 and M1 commands When executing M0/M1 commands and no print is paused, execute stop.g/sleep.g if they exist Treat M25 within the file being printed the same as M226 Added additional simulation modes to help identify bottlenecks Don't disable all interrupts when starting a new move, to reduce interrupt latency so that we can still receive data from PanelDue Moved some utility maths functions to CoreNG
-rw-r--r--.cproject117
-rw-r--r--.settings/language.settings.xml11
-rw-r--r--SD-image/sys-dc42Kossel/config.g1
-rw-r--r--src/Configuration.h13
-rw-r--r--src/DDA.cpp26
-rw-r--r--src/DDA.h13
-rw-r--r--src/Duet/EMAC/ethernet_phy.h5
-rw-r--r--src/Duet/Network.cpp8
-rw-r--r--src/Duet/Network.h2
-rw-r--r--src/Duet/Pins_Duet.h3
-rw-r--r--src/Duet/Webserver.cpp22
-rw-r--r--src/Duet/Webserver.h10
-rw-r--r--src/ExternalDrivers.cpp2
-rw-r--r--src/FileStore.h2
-rw-r--r--src/GCodeBuffer.cpp22
-rw-r--r--src/GCodeBuffer.h41
-rw-r--r--src/GCodes.cpp1113
-rw-r--r--src/GCodes.h40
-rw-r--r--src/Heat.cpp6
-rw-r--r--src/Heat.h2
-rw-r--r--src/Libraries/Flash/DueFlashStorage.h2
-rw-r--r--src/Libraries/TemperatureSensor/TemperatureSensor.h2
-rw-r--r--src/MessageType.h24
-rw-r--r--src/Move.cpp103
-rw-r--r--src/Move.h7
-rw-r--r--src/OutputMemory.cpp4
-rw-r--r--src/OutputMemory.h5
-rw-r--r--src/Platform.cpp212
-rw-r--r--src/Platform.h38
-rw-r--r--src/RepRapFirmware.h70
-rw-r--r--src/Reprap.cpp18
-rw-r--r--src/Reprap.h2
-rw-r--r--src/StringRef.cpp12
-rw-r--r--src/StringRef.h1
34 files changed, 1080 insertions, 879 deletions
diff --git a/.cproject b/.cproject
index 9148db89..fdb51e37 100644
--- a/.cproject
+++ b/.cproject
@@ -1,117 +1,6 @@
<?xml version="1.0" encoding="UTF-8" standalone="no"?>
<?fileVersion 4.0.0?><cproject storage_type_id="org.eclipse.cdt.core.XmlProjectDescriptionStorage">
<storageModule moduleId="org.eclipse.cdt.core.settings">
- <cconfiguration id="cdt.managedbuild.config.gnu.cross.exe.release.516195201">
- <storageModule buildSystemId="org.eclipse.cdt.managedbuilder.core.configurationDataProvider" id="cdt.managedbuild.config.gnu.cross.exe.release.516195201" moduleId="org.eclipse.cdt.core.settings" name="ReleaseWithCoreDuet">
- <macros>
- <stringMacro name="CoreName" type="VALUE_TEXT" value="CoreDuet"/>
- </macros>
- <externalSettings/>
- <extensions>
- <extension id="org.eclipse.cdt.core.GmakeErrorParser" point="org.eclipse.cdt.core.ErrorParser"/>
- <extension id="org.eclipse.cdt.core.CWDLocator" 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.GASErrorParser" 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.ELF" point="org.eclipse.cdt.core.BinaryParser"/>
- </extensions>
- </storageModule>
- <storageModule moduleId="cdtBuildSystem" version="4.0.0">
- <configuration artifactExtension="elf" artifactName="${ProjName}" buildArtefactType="org.eclipse.cdt.build.core.buildArtefactType.exe" buildProperties="org.eclipse.cdt.build.core.buildType=org.eclipse.cdt.build.core.buildType.release,org.eclipse.cdt.build.core.buildArtefactType=org.eclipse.cdt.build.core.buildArtefactType.exe" cleanCommand="rm -rf" description="" id="cdt.managedbuild.config.gnu.cross.exe.release.516195201" name="ReleaseWithCoreDuet" parent="cdt.managedbuild.config.gnu.cross.exe.release" postannouncebuildStep="Generating binary file" postbuildStep="arm-none-eabi-objcopy -O binary ${workspace_loc:/${ProjName}/${ConfigName}}/${ProjName}.elf ${workspace_loc:/${ProjName}/${ConfigName}}/${ProjName}.bin">
- <folderInfo id="cdt.managedbuild.config.gnu.cross.exe.release.516195201." name="/" resourcePath="">
- <toolChain id="cdt.managedbuild.toolchain.gnu.cross.exe.release.56337087" name="Cross GCC" superClass="cdt.managedbuild.toolchain.gnu.cross.exe.release">
- <option id="cdt.managedbuild.option.gnu.cross.path.716610183" name="Path" superClass="cdt.managedbuild.option.gnu.cross.path" value="C:\Arduino-1.5.8\hardware\tools\gcc-arm-none-eabi-4.8.3-2014q1\bin" valueType="string"/>
- <option id="cdt.managedbuild.option.gnu.cross.prefix.1300241300" name="Prefix" superClass="cdt.managedbuild.option.gnu.cross.prefix" value="arm-none-eabi-" valueType="string"/>
- <targetPlatform archList="all" binaryParser="org.eclipse.cdt.core.ELF" id="cdt.managedbuild.targetPlatform.gnu.cross.1581645614" isAbstract="false" osList="all" superClass="cdt.managedbuild.targetPlatform.gnu.cross"/>
- <builder buildPath="${workspace_loc:/RepRapFirmware}/Release" id="cdt.managedbuild.builder.gnu.cross.527170141" keepEnvironmentInBuildfile="false" managedBuildOn="true" name="Gnu Make Builder" superClass="cdt.managedbuild.builder.gnu.cross"/>
- <tool id="cdt.managedbuild.tool.gnu.cross.assembler.1967891077" name="Cross GCC Assembler" superClass="cdt.managedbuild.tool.gnu.cross.assembler">
- <inputType id="cdt.managedbuild.tool.gnu.assembler.input.729788515" superClass="cdt.managedbuild.tool.gnu.assembler.input"/>
- </tool>
- <tool commandLinePattern="${COMMAND} ${FLAGS} ${OUTPUT_FLAG} ${OUTPUT_PREFIX}${OUTPUT} ${INPUTS}" id="cdt.managedbuild.tool.gnu.cross.c.compiler.220085372" name="Cross GCC Compiler" superClass="cdt.managedbuild.tool.gnu.cross.c.compiler">
- <option defaultValue="gnu.c.optimization.level.most" id="gnu.c.compiler.option.optimization.level.1490670229" name="Optimization Level" superClass="gnu.c.compiler.option.optimization.level" useByScannerDiscovery="false" valueType="enumerated"/>
- <option id="gnu.c.compiler.option.debugging.level.1765216517" name="Debug Level" superClass="gnu.c.compiler.option.debugging.level" useByScannerDiscovery="false" value="gnu.c.debugging.level.none" valueType="enumerated"/>
- <option id="gnu.c.compiler.option.misc.verbose.1564280355" name="Verbose (-v)" superClass="gnu.c.compiler.option.misc.verbose" useByScannerDiscovery="false" value="false" valueType="boolean"/>
- <option id="gnu.c.compiler.option.misc.other.96683616" name="Other flags" superClass="gnu.c.compiler.option.misc.other" useByScannerDiscovery="false" value="-c -std=gnu99 -mcpu=cortex-m3 -mthumb -ffunction-sections -fdata-sections -nostdlib --param max-inline-insns-single=500" valueType="string"/>
- <option id="gnu.c.compiler.option.include.paths.187319219" name="Include paths (-I)" superClass="gnu.c.compiler.option.include.paths" useByScannerDiscovery="false" valueType="includePath">
- <listOptionValue builtIn="false" value="&quot;${workspace_loc:/${CoreName}/cores/arduino}&quot;"/>
- <listOptionValue builtIn="false" value="&quot;${workspace_loc:/${CoreName}/system/libsam}&quot;"/>
- <listOptionValue builtIn="false" value="&quot;${workspace_loc:/${CoreName}/system/CMSIS/Device/ATMEL}&quot;"/>
- <listOptionValue builtIn="false" value="&quot;${workspace_loc:/${CoreName}/system/CMSIS/CMSIS/Include}&quot;"/>
- <listOptionValue builtIn="false" value="&quot;${workspace_loc:/${CoreName}/variants/duet}&quot;"/>
- <listOptionValue builtIn="false" value="&quot;${workspace_loc:/${CoreName}/system/libsam/include}&quot;"/>
- <listOptionValue builtIn="false" value="&quot;${workspace_loc:/${CoreName}/system/CMSIS/Device/ATMEL/sam3xa/include}&quot;"/>
- <listOptionValue builtIn="false" value="&quot;${workspace_loc:/${CoreName}/libraries/Storage}&quot;"/>
- <listOptionValue builtIn="false" value="&quot;${workspace_loc:/${ProjName}/src/Duet/Lwip}&quot;"/>
- <listOptionValue builtIn="false" value="&quot;${workspace_loc:/${ProjName}/src/Duet/Lwip/lwip/src/include}&quot;"/>
- <listOptionValue builtIn="false" value="&quot;${workspace_loc:/${ProjName}/src/Duet/EMAC}&quot;"/>
- </option>
- <option id="gnu.c.compiler.option.preprocessor.def.symbols.2036576066" name="Defined symbols (-D)" superClass="gnu.c.compiler.option.preprocessor.def.symbols" useByScannerDiscovery="false" valueType="definedSymbols">
- <listOptionValue builtIn="false" value="__SAM3X8E__"/>
- <listOptionValue builtIn="false" value="F_CPU=84000000"/>
- <listOptionValue builtIn="false" value="USBCON"/>
- <listOptionValue builtIn="false" value="USB_PID=0x003e"/>
- <listOptionValue builtIn="false" value="USB_VID=0x2341"/>
- <listOptionValue builtIn="false" value="printf=iprintf"/>
- </option>
- <inputType id="cdt.managedbuild.tool.gnu.c.compiler.input.1345445195" superClass="cdt.managedbuild.tool.gnu.c.compiler.input"/>
- </tool>
- <tool id="cdt.managedbuild.tool.gnu.cross.c.linker.244306990" name="Cross GCC Linker" superClass="cdt.managedbuild.tool.gnu.cross.c.linker"/>
- <tool id="cdt.managedbuild.tool.gnu.cross.archiver.1297529102" name="Cross GCC Archiver" superClass="cdt.managedbuild.tool.gnu.cross.archiver"/>
- <tool command="gcc" commandLinePattern="${COMMAND} ${FLAGS} ${OUTPUT_FLAG} ${OUTPUT_PREFIX}${OUTPUT} ${LINK_FLAGS_1} ${workspace_loc:/${CoreName}/Release/cores/arduino/syscalls.o} ${INPUTS} ${LINK_FLAGS_2}" id="cdt.managedbuild.tool.gnu.cross.cpp.linker.1456918662" name="Cross G++ Linker" superClass="cdt.managedbuild.tool.gnu.cross.cpp.linker">
- <option id="gnu.cpp.link.option.nostdlibs.1511064380" name="No startup or default libs (-nostdlib)" superClass="gnu.cpp.link.option.nostdlibs" value="false" valueType="boolean"/>
- <option id="gnu.cpp.link.option.paths.178730582" name="Library search path (-L)" superClass="gnu.cpp.link.option.paths" valueType="libPaths">
- <listOptionValue builtIn="false" value="&quot;${workspace_loc:/${CoreName}/Release/}&quot;"/>
- </option>
- <option id="gnu.cpp.link.option.libs.1614032345" name="Libraries (-l)" superClass="gnu.cpp.link.option.libs" valueType="libs">
- <listOptionValue builtIn="false" value="${CoreName}"/>
- </option>
- <option id="gnu.cpp.link.option.flags.1874922881" name="Linker flags" superClass="gnu.cpp.link.option.flags" value="-Os -Wl,--gc-sections -Wl,--fatal-warnings -mcpu=cortex-m3 -T${workspace_loc:/CoreDuet/variants/duet/linker_scripts/gcc/flash.ld} -Wl,-Map,${workspace_loc:/${ProjName}/${ConfigName}}/${ProjName}.map" valueType="string"/>
- <inputType id="cdt.managedbuild.tool.gnu.cpp.linker.input.1479906997" superClass="cdt.managedbuild.tool.gnu.cpp.linker.input">
- <additionalInput kind="additionalinputdependency" paths="$(USER_OBJS)"/>
- <additionalInput kind="additionalinput" paths="$(LIBS)"/>
- </inputType>
- </tool>
- <tool command="g++" id="cdt.managedbuild.tool.gnu.cross.cpp.compiler.1703390221" name="Cross G++ Compiler" superClass="cdt.managedbuild.tool.gnu.cross.cpp.compiler">
- <option id="gnu.cpp.compiler.option.optimization.level.1076886860" name="Optimization Level" superClass="gnu.cpp.compiler.option.optimization.level" useByScannerDiscovery="false" value="gnu.cpp.compiler.optimization.level.more" valueType="enumerated"/>
- <option id="gnu.cpp.compiler.option.debugging.level.1252771497" name="Debug Level" superClass="gnu.cpp.compiler.option.debugging.level" useByScannerDiscovery="false" value="gnu.cpp.compiler.debugging.level.none" valueType="enumerated"/>
- <option id="gnu.cpp.compiler.option.other.verbose.526148117" name="Verbose (-v)" superClass="gnu.cpp.compiler.option.other.verbose" useByScannerDiscovery="false" value="false" valueType="boolean"/>
- <option id="gnu.cpp.compiler.option.other.other.1337488452" name="Other flags" superClass="gnu.cpp.compiler.option.other.other" useByScannerDiscovery="false" value="-c -std=gnu++11 -mcpu=cortex-m3 -mthumb -ffunction-sections -fdata-sections -fno-threadsafe-statics -fno-rtti -fno-exceptions -nostdlib --param max-inline-insns-single=500" valueType="string"/>
- <option id="gnu.cpp.compiler.option.include.paths.148186010" name="Include paths (-I)" superClass="gnu.cpp.compiler.option.include.paths" useByScannerDiscovery="false" valueType="includePath">
- <listOptionValue builtIn="false" value="&quot;${workspace_loc:/${CoreName}/cores/arduino}&quot;"/>
- <listOptionValue builtIn="false" value="&quot;${workspace_loc:/${CoreName}/libraries/Wire}&quot;"/>
- <listOptionValue builtIn="false" value="&quot;${workspace_loc:/${CoreName}/system/libsam}&quot;"/>
- <listOptionValue builtIn="false" value="&quot;${workspace_loc:/${CoreName}/system/CMSIS/Device/ATMEL}&quot;"/>
- <listOptionValue builtIn="false" value="&quot;${workspace_loc:/${CoreName}/system/CMSIS/CMSIS/Include}&quot;"/>
- <listOptionValue builtIn="false" value="&quot;${workspace_loc:/${CoreName}/variants/duet}&quot;"/>
- <listOptionValue builtIn="false" value="&quot;${workspace_loc:/${CoreName}/system/libsam/include}&quot;"/>
- <listOptionValue builtIn="false" value="&quot;${workspace_loc:/${ProjName}/src}&quot;"/>
- <listOptionValue builtIn="false" value="&quot;${workspace_loc:/${ProjName}/src/Duet}&quot;"/>
- <listOptionValue builtIn="false" value="&quot;${workspace_loc:/${ProjName}/src/Duet/Lwip}&quot;"/>
- <listOptionValue builtIn="false" value="&quot;${workspace_loc:/${ProjName}/src/Duet/EMAC}&quot;"/>
- <listOptionValue builtIn="false" value="&quot;${workspace_loc:/${ProjName}/src/Libraries/Fatfs}&quot;"/>
- <listOptionValue builtIn="false" value="&quot;${workspace_loc:/${ProjName}/src/Libraries/MAX31855}&quot;"/>
- <listOptionValue builtIn="false" value="&quot;${workspace_loc:/${ProjName}/src/Libraries/MCP4461}&quot;"/>
- <listOptionValue builtIn="false" value="&quot;${workspace_loc:/${ProjName}/src/Libraries/Flash}&quot;"/>
- </option>
- <option id="gnu.cpp.compiler.option.preprocessor.def.1913656094" name="Defined symbols (-D)" superClass="gnu.cpp.compiler.option.preprocessor.def" useByScannerDiscovery="false" valueType="definedSymbols">
- <listOptionValue builtIn="false" value="__SAM3X8E__"/>
- <listOptionValue builtIn="false" value="F_CPU=84000000"/>
- <listOptionValue builtIn="false" value="USBCON"/>
- <listOptionValue builtIn="false" value="USB_PID=0x003e"/>
- <listOptionValue builtIn="false" value="USB_VID=0x2341"/>
- <listOptionValue builtIn="false" value="printf=iprintf"/>
- </option>
- <inputType id="cdt.managedbuild.tool.gnu.cpp.compiler.input.111814721" superClass="cdt.managedbuild.tool.gnu.cpp.compiler.input"/>
- </tool>
- </toolChain>
- </folderInfo>
- <sourceEntries>
- <entry excluding="src/Duet/Lwip/lwip/src/core/ipv6|src/Duet/Lwip/lwip/test|src/DuetNG`" flags="VALUE_WORKSPACE_PATH|RESOLVED" kind="sourcePath" name=""/>
- </sourceEntries>
- </configuration>
- </storageModule>
- <storageModule moduleId="org.eclipse.cdt.core.externalSettings"/>
- </cconfiguration>
<cconfiguration id="cdt.managedbuild.config.gnu.cross.exe.release.516195201.976458850">
<storageModule buildSystemId="org.eclipse.cdt.managedbuilder.core.configurationDataProvider" id="cdt.managedbuild.config.gnu.cross.exe.release.516195201.976458850" moduleId="org.eclipse.cdt.core.settings" name="SAM3X_CoreNG">
<macros>
@@ -164,8 +53,6 @@
</option>
<option id="gnu.c.compiler.option.preprocessor.def.symbols.571434619" name="Defined symbols (-D)" superClass="gnu.c.compiler.option.preprocessor.def.symbols" useByScannerDiscovery="false" valueType="definedSymbols">
<listOptionValue builtIn="false" value="__SAM3X8E__"/>
- <listOptionValue builtIn="false" value="F_CPU=84000000"/>
- <listOptionValue builtIn="false" value="CORE_NG"/>
<listOptionValue builtIn="false" value="printf=iprintf"/>
</option>
<inputType id="cdt.managedbuild.tool.gnu.c.compiler.input.1642892736" superClass="cdt.managedbuild.tool.gnu.c.compiler.input"/>
@@ -221,8 +108,6 @@
</option>
<option id="gnu.cpp.compiler.option.preprocessor.def.1548770846" name="Defined symbols (-D)" superClass="gnu.cpp.compiler.option.preprocessor.def" useByScannerDiscovery="false" valueType="definedSymbols">
<listOptionValue builtIn="false" value="__SAM3X8E__"/>
- <listOptionValue builtIn="false" value="F_CPU=84000000"/>
- <listOptionValue builtIn="false" value="CORE_NG"/>
<listOptionValue builtIn="false" value="printf=iprintf"/>
</option>
<inputType id="cdt.managedbuild.tool.gnu.cpp.compiler.input.948285998" superClass="cdt.managedbuild.tool.gnu.cpp.compiler.input"/>
@@ -285,7 +170,6 @@
</option>
<option id="gnu.c.compiler.option.preprocessor.def.symbols.1695995740" name="Defined symbols (-D)" superClass="gnu.c.compiler.option.preprocessor.def.symbols" useByScannerDiscovery="false" valueType="definedSymbols">
<listOptionValue builtIn="false" value="__SAM4E8E__"/>
- <listOptionValue builtIn="false" value="F_CPU=120000000"/>
<listOptionValue builtIn="false" value="CORE_NG"/>
<listOptionValue builtIn="false" value="DUET_NG"/>
<listOptionValue builtIn="false" value="printf=iprintf"/>
@@ -341,7 +225,6 @@
</option>
<option id="gnu.cpp.compiler.option.preprocessor.def.1610427238" name="Defined symbols (-D)" superClass="gnu.cpp.compiler.option.preprocessor.def" useByScannerDiscovery="false" valueType="definedSymbols">
<listOptionValue builtIn="false" value="__SAM4E8E__"/>
- <listOptionValue builtIn="false" value="F_CPU=120000000"/>
<listOptionValue builtIn="false" value="CORE_NG"/>
<listOptionValue builtIn="false" value="DUET_NG"/>
<listOptionValue builtIn="false" value="printf=iprintf"/>
diff --git a/.settings/language.settings.xml b/.settings/language.settings.xml
index 02bb3c11..585ff377 100644
--- a/.settings/language.settings.xml
+++ b/.settings/language.settings.xml
@@ -1,16 +1,5 @@
<?xml version="1.0" encoding="UTF-8" standalone="no"?>
<project>
- <configuration id="cdt.managedbuild.config.gnu.cross.exe.release.516195201" name="ReleaseWithCoreDuet">
- <extension point="org.eclipse.cdt.core.LanguageSettingsProvider">
- <provider copy-of="extension" id="org.eclipse.cdt.ui.UserLanguageSettingsProvider"/>
- <provider-reference id="org.eclipse.cdt.core.ReferencedProjectsLanguageSettingsProvider" ref="shared-provider"/>
- <provider-reference id="org.eclipse.cdt.managedbuilder.core.MBSLanguageSettingsProvider" ref="shared-provider"/>
- <provider class="org.eclipse.cdt.internal.build.crossgcc.CrossGCCBuiltinSpecsDetector" console="false" env-hash="337623625225680352" id="org.eclipse.cdt.build.crossgcc.CrossGCCBuiltinSpecsDetector" keep-relative-paths="false" name="CDT Cross GCC Built-in Compiler Settings" parameter="${COMMAND} ${FLAGS} -E -P -v -dD &quot;${INPUTS}&quot;" prefer-non-shared="true">
- <language-scope id="org.eclipse.cdt.core.gcc"/>
- <language-scope id="org.eclipse.cdt.core.g++"/>
- </provider>
- </extension>
- </configuration>
<configuration id="cdt.managedbuild.config.gnu.cross.exe.release.516195201.976458850" name="SAM3X_CoreNG">
<extension point="org.eclipse.cdt.core.LanguageSettingsProvider">
<provider copy-of="extension" id="org.eclipse.cdt.ui.UserLanguageSettingsProvider"/>
diff --git a/SD-image/sys-dc42Kossel/config.g b/SD-image/sys-dc42Kossel/config.g
index 53694012..23c8bb35 100644
--- a/SD-image/sys-dc42Kossel/config.g
+++ b/SD-image/sys-dc42Kossel/config.g
@@ -34,6 +34,7 @@ M83 ; ...but relative extruder moves
; Thermistors and heaters
M305 P0 T100000 B3950 R4700 H0 L0 ; Typical Chinese bed thermistor. Put your own H and/or L values here to set the bed thermistor ADC correction.
M305 P1 T100000 B4388 R4700 H0 L0 ; E3Dv6 hot end. Put your own H and/or L values here if necessary to set the first nozzle thermistor ADC correction.
+M301 H0 P20 I0.5 D1000 T0.85 W150 B5 ; PID settings for the bed
M301 H1 P10 I0.10 D100 T0.50 ; PID settings for extruder 0
M570 S200 ; Allow extra heating time
diff --git a/src/Configuration.h b/src/Configuration.h
index 71ffc4ea..e972ca60 100644
--- a/src/Configuration.h
+++ b/src/Configuration.h
@@ -26,11 +26,11 @@ Licence: GPL
// Firmware name is now defined in the Pins file
#ifndef VERSION
-# define VERSION "1.12a"
+# define VERSION "1.13beta1"
#endif
#ifndef DATE
-# define DATE "2016-05-10"
+# define DATE "2016-05-27"
#endif
#define AUTHORS "reprappro, dc42, zpl, t3p3, dnewman"
@@ -123,8 +123,13 @@ const size_t FILENAME_LENGTH = 100;
// Output buffer lengths
+#ifdef DUET_NG
+const uint16_t OUTPUT_BUFFER_SIZE = 256; // How many bytes does each OutputBuffer hold?
+const size_t OUTPUT_BUFFER_COUNT = 32; // How many OutputBuffer instances do we have?
+#else
const uint16_t OUTPUT_BUFFER_SIZE = 128; // How many bytes does each OutputBuffer hold?
const size_t OUTPUT_BUFFER_COUNT = 32; // How many OutputBuffer instances do we have?
+#endif
// Move system
@@ -132,6 +137,10 @@ const float DEFAULT_FEEDRATE = 3000.0; // The initial requested feed rate aft
const float DEFAULT_IDLE_TIMEOUT = 30.0; // Seconds
const float DEFAULT_IDLE_CURRENT_FACTOR = 0.3; // Proportion of normal motor current that we use for idle hold
+// Triggers
+
+const unsigned int MaxTriggers = 10; // Must be <= 32 because we store a bitmap of pending triggers in a uint32_t
+
// Default nozzle and filament values
const float NOZZLE_DIAMETER = 0.5; // Millimetres
diff --git a/src/DDA.cpp b/src/DDA.cpp
index d54efc57..078adb0c 100644
--- a/src/DDA.cpp
+++ b/src/DDA.cpp
@@ -171,6 +171,7 @@ bool DDA::Init(const GCodes::RawMove &nextMove, bool doMotorMapping)
endStopsToCheck = nextMove.endStopsToCheck;
filePos = nextMove.filePos;
usePressureAdvance = nextMove.usePressureAdvance;
+ hadLookaheadUnderrun = false;
// 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 = (endStopsToCheck == 0) && (doMotorMapping || !move->IsDeltaMode());
@@ -358,18 +359,29 @@ void DDA::DoLookahead(DDA *laDDA)
laDDA->endSpeed = laDDA->requestedSpeed; // remove the deceleration phase
laDDA->CalcNewSpeeds(); // put it back if necessary
}
- else if (laDDA->decelDistance == laDDA->totalDistance && laDDA->prev->state == provisional)
+ else if (laDDA->decelDistance == laDDA->totalDistance)
{
// This is a deceleration-only move, so we may have to adjust the previous move as well to get optimum behaviour
- laDDA->endSpeed = laDDA->requestedSpeed;
- laDDA->CalcNewSpeeds();
- laDDA->prev->targetNextSpeed = min<float>(sqrtf(fsquare(laDDA->endSpeed) + (2 * laDDA->acceleration * laDDA->totalDistance)),
- laDDA->requestedSpeed);
- recurse = true;
+ if (laDDA->prev->state == provisional)
+ {
+ laDDA->endSpeed = laDDA->requestedSpeed;
+ laDDA->CalcNewSpeeds();
+ laDDA->prev->targetNextSpeed = min<float>(sqrtf(fsquare(laDDA->endSpeed) + (2 * laDDA->acceleration * laDDA->totalDistance)),
+ laDDA->requestedSpeed);
+ recurse = true;
+ }
+ else
+ {
+ // This move is a deceleration-only move but we can't adjust the previous one
+ laDDA->hadLookaheadUnderrun = true;
+ laDDA->endSpeed = min<float>(sqrtf(fsquare(laDDA->startSpeed) + (2 * laDDA->acceleration * laDDA->totalDistance)),
+ laDDA->requestedSpeed);
+ laDDA->CalcNewSpeeds();
+ }
}
else
{
- // This move doesn't reach its requested speed, but it isn't a deceleration-only move, or we can't adjust the previous one
+ // This move doesn't reach its requested speed, but it isn't a deceleration-only move
laDDA->endSpeed = min<float>(sqrtf(fsquare(laDDA->startSpeed) + (2 * laDDA->acceleration * laDDA->totalDistance)),
laDDA->requestedSpeed);
laDDA->CalcNewSpeeds();
diff --git a/src/DDA.h b/src/DDA.h
index ddb39131..62a58f2f 100644
--- a/src/DDA.h
+++ b/src/DDA.h
@@ -37,7 +37,7 @@ public:
void SetNext(DDA *n) { next = n; }
void SetPrevious(DDA *p) { prev = p; }
void Complete() { state = completed; }
- void Free() { state = empty; }
+ bool Free();
void Prepare(); // Calculate all the values and freeze this DDA
float CalcTime() const; // Calculate the time needed for this move (used for simulation)
bool HasStepError() const;
@@ -65,7 +65,7 @@ public:
// Note on the following constant:
// If we calculate the step interval on every clock, we reach a point where the calculation time exceeds the step interval.
- // The worst case is pure Z movement on a delta. On a Mini Kossel with 80 steps/mm witt this formware runnig on a Duet (84MHx SAM3X8 processor),
+ // The worst case is pure Z movement on a delta. On a Mini Kossel with 80 steps/mm with this firmware running on a Duet (84MHx SAM3X8 processor),
// the calculation can just be managed in time at speeds of 15000mm/min (step interval 50us), but not at 20000mm/min (step interval 37.5us).
// Therefore, where the step interval falls below 70us, we don't calculate on every step.
static const int32_t MinCalcInterval = (70 * stepClockRate)/1000000; // the smallest sensible interval between calculations (70us) in step timer clocks
@@ -99,6 +99,7 @@ private:
uint8_t goingSlow : 1; // True if we have reduced speed during homing
uint8_t isPrintingMove : 1; // True if this move includes XY movement and extrusion
uint8_t usePressureAdvance : 1; // True if pressure advance should be applied to any forward extrusion
+ uint8_t hadLookaheadUnderrun : 1; // True if the lookahead queue was not long enough to optimise this move
EndstopChecks endStopsToCheck; // Which endstops we are checking on this move
@@ -134,6 +135,14 @@ private:
DriveMovement ddm[DRIVES]; // These describe the state of each drive movement
};
+// Free up this DDA, returning true if the lookahead underrun flag was set
+inline bool DDA::Free()
+{
+ state = empty;
+ return hadLookaheadUnderrun;
+}
+
+
// Force an end point
inline void DDA::SetDriveCoordinate(int32_t a, size_t drive)
{
diff --git a/src/Duet/EMAC/ethernet_phy.h b/src/Duet/EMAC/ethernet_phy.h
index 64c565a4..bf9f5567 100644
--- a/src/Duet/EMAC/ethernet_phy.h
+++ b/src/Duet/EMAC/ethernet_phy.h
@@ -46,10 +46,7 @@
#ifndef KSZ8051RNL_H_INCLUDED
#define KSZ8051RNL_H_INCLUDED
-//#include "ASF/sam/utils/compiler.h"
-//#include "board.h"
-//#include "emac.h"
-#include "Arduino.h"
+#include "Core.h"
#include "emac.h"
#include "conf_eth.h"
diff --git a/src/Duet/Network.cpp b/src/Duet/Network.cpp
index 86b862d3..a3901b24 100644
--- a/src/Duet/Network.cpp
+++ b/src/Duet/Network.cpp
@@ -497,9 +497,9 @@ void Network::Interrupt()
}
}
-void Network::Diagnostics()
+void Network::Diagnostics(MessageType mtype)
{
- platform->Message(GENERIC_MESSAGE, "Network Diagnostics:\n");
+ platform->Message(mtype, "Network Diagnostics:\n");
size_t numFreeConnections = 0;
ConnectionState *freeConn = freeConnections;
@@ -508,7 +508,7 @@ void Network::Diagnostics()
numFreeConnections++;
freeConn = freeConn->next;
}
- platform->MessageF(GENERIC_MESSAGE, "Free connections: %d of %d\n", numFreeConnections, MEMP_NUM_TCP_PCB);
+ platform->MessageF(mtype, "Free connections: %d of %d\n", numFreeConnections, MEMP_NUM_TCP_PCB);
size_t numFreeTransactions = 0;
NetworkTransaction *freeTrans = freeTransactions;
@@ -517,7 +517,7 @@ void Network::Diagnostics()
numFreeTransactions++;
freeTrans = freeTrans->next;
}
- platform->MessageF(GENERIC_MESSAGE, "Free transactions: %d of %d\n", numFreeTransactions, NETWORK_TRANSACTION_COUNT);
+ platform->MessageF(mtype, "Free transactions: %d of %d\n", numFreeTransactions, NETWORK_TRANSACTION_COUNT);
#if LWIP_STATS
// Normally we should NOT try to display LWIP stats here, because it uses debugPrintf(), which will hang the system if no USB cable is connected.
diff --git a/src/Duet/Network.h b/src/Duet/Network.h
index 7885f8b3..0d1f77c9 100644
--- a/src/Duet/Network.h
+++ b/src/Duet/Network.h
@@ -153,7 +153,7 @@ class Network
void Exit() {}
void Spin();
void Interrupt();
- void Diagnostics();
+ void Diagnostics(MessageType mtype);
// Deal with LwIP
diff --git a/src/Duet/Pins_Duet.h b/src/Duet/Pins_Duet.h
index 79637b2c..75ef1853 100644
--- a/src/Duet/Pins_Duet.h
+++ b/src/Duet/Pins_Duet.h
@@ -3,6 +3,7 @@
#define NAME "RepRapFirmware for Duet"
+const size_t NumFirmwareUpdateModules = 1;
#define IAP_UPDATE_FILE "iap.bin"
#define IAP_FIRMWARE_FILE "RepRapFirmware.bin"
@@ -156,7 +157,7 @@ const size_t NUM_PINS_ALLOWED = 72;
// SAM3X Flash locations (may be expanded in the future)
const uint32_t IAP_FLASH_START = 0x000F0000;
-const uint32_t IAP_FLASH_END = 0x000FFFFF;
+const uint32_t IAP_FLASH_END = 0x000FFBFF; // don't touch the last 1KB, it's used for NvData
// Timer allocation
#define NETWORK_TC (TC1)
diff --git a/src/Duet/Webserver.cpp b/src/Duet/Webserver.cpp
index d3352163..9e0150e7 100644
--- a/src/Duet/Webserver.cpp
+++ b/src/Duet/Webserver.cpp
@@ -251,12 +251,12 @@ void Webserver::Exit()
webserverActive = false;
}
-void Webserver::Diagnostics()
+void Webserver::Diagnostics(MessageType mtype)
{
- platform->Message(GENERIC_MESSAGE, "Webserver Diagnostics:\n");
- httpInterpreter->Diagnostics();
- ftpInterpreter->Diagnostics();
- telnetInterpreter->Diagnostics();
+ platform->Message(mtype, "Webserver Diagnostics:\n");
+ httpInterpreter->Diagnostics(mtype);
+ ftpInterpreter->Diagnostics(mtype);
+ telnetInterpreter->Diagnostics(mtype);
}
bool Webserver::GCodeAvailable(const WebSource source) const
@@ -535,9 +535,9 @@ Webserver::HttpInterpreter::HttpInterpreter(Platform *p, Webserver *ws, Network
seq = 0;
}
-void Webserver::HttpInterpreter::Diagnostics()
+void Webserver::HttpInterpreter::Diagnostics(MessageType mt)
{
- platform->MessageF(GENERIC_MESSAGE, "HTTP sessions: %d of %d\n", numSessions, maxHttpSessions);
+ platform->MessageF(mt, "HTTP sessions: %d of %d\n", numSessions, maxHttpSessions);
}
void Webserver::HttpInterpreter::Spin()
@@ -1848,9 +1848,9 @@ Webserver::FtpInterpreter::FtpInterpreter(Platform *p, Webserver *ws, Network *n
strcpy(currentDir, "/");
}
-void Webserver::FtpInterpreter::Diagnostics()
+void Webserver::FtpInterpreter::Diagnostics(MessageType mt)
{
- platform->MessageF(GENERIC_MESSAGE, "FTP connections: %d, state %d\n", connectedClients, state);
+ platform->MessageF(mt, "FTP connections: %d, state %d\n", connectedClients, state);
}
void Webserver::FtpInterpreter::ConnectionEstablished()
@@ -2497,9 +2497,9 @@ gcodeReadIndex(0), gcodeWriteIndex(0), gcodeReply(nullptr)
ResetState();
}
-void Webserver::TelnetInterpreter::Diagnostics()
+void Webserver::TelnetInterpreter::Diagnostics(MessageType mt)
{
- platform->MessageF(GENERIC_MESSAGE, "Telnet connections: %d, state %d\n", connectedClients, state);
+ platform->MessageF(mt, "Telnet connections: %d, state %d\n", connectedClients, state);
}
void Webserver::TelnetInterpreter::ConnectionEstablished()
diff --git a/src/Duet/Webserver.h b/src/Duet/Webserver.h
index d6f98ac2..0801108e 100644
--- a/src/Duet/Webserver.h
+++ b/src/Duet/Webserver.h
@@ -78,7 +78,7 @@ class ProtocolInterpreter
ProtocolInterpreter(Platform *p, Webserver *ws, Network *n);
virtual ~ProtocolInterpreter() { } // to keep Eclipse happy
- virtual void Diagnostics() = 0;
+ virtual void Diagnostics(MessageType mtype) = 0;
virtual void Spin();
virtual void ConnectionEstablished();
@@ -125,7 +125,7 @@ class Webserver
void Init();
void Spin();
void Exit();
- void Diagnostics();
+ void Diagnostics(MessageType mtype);
bool GCodeAvailable(const WebSource source) const;
char ReadGCode(const WebSource source);
@@ -147,7 +147,7 @@ class Webserver
HttpInterpreter(Platform *p, Webserver *ws, Network *n);
void Spin();
- void Diagnostics();
+ void Diagnostics(MessageType mtype) override;
void ConnectionLost(const ConnectionState *cs);
bool CanParseData() override;
bool CharFromClient(const char c) override;
@@ -261,7 +261,7 @@ class Webserver
public:
FtpInterpreter(Platform *p, Webserver *ws, Network *n);
- void Diagnostics();
+ void Diagnostics(MessageType mtype) override;
void ConnectionEstablished() override;
void ConnectionLost(const ConnectionState *cs) override;
@@ -306,7 +306,7 @@ class Webserver
public:
TelnetInterpreter(Platform *p, Webserver *ws, Network *n);
- void Diagnostics();
+ void Diagnostics(MessageType mtype) override;
void ConnectionEstablished() override;
void ConnectionLost(const ConnectionState *cs) override;
diff --git a/src/ExternalDrivers.cpp b/src/ExternalDrivers.cpp
index 985803a4..04634fa0 100644
--- a/src/ExternalDrivers.cpp
+++ b/src/ExternalDrivers.cpp
@@ -210,7 +210,7 @@ uint32_t SpiSendWord(uint32_t pin, uint32_t dataOut)
digitalWrite(pin, HIGH); // set CS high again
USART_EXT_DRV->US_CR = US_CR_RSTRX | US_CR_RSTTX | US_CR_RXDIS | US_CR_TXDIS; // reset and disable transmitter and receiver
delayMicroseconds(1); // ensure it stays high for long enough before the next write
- return (dataIn >> 4) & 0x000FFFFF;
+ return dataIn >> 4;
}
struct TmcDriverState
diff --git a/src/FileStore.h b/src/FileStore.h
index e1de5fa1..470c9c20 100644
--- a/src/FileStore.h
+++ b/src/FileStore.h
@@ -3,7 +3,7 @@
#ifndef FILESTORE_H
#define FILESTORE_H
-#include "Arduino.h"
+#include "Core.h"
#include "ff.h"
typedef uint32_t FilePosition;
diff --git a/src/GCodeBuffer.cpp b/src/GCodeBuffer.cpp
index 724b779b..6ebedb31 100644
--- a/src/GCodeBuffer.cpp
+++ b/src/GCodeBuffer.cpp
@@ -11,8 +11,8 @@
// 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), checksumRequired(false), writingFileDirectory(nullptr), toolNumberAdjust(0)
+GCodeBuffer::GCodeBuffer(Platform* p, const char* id, MessageType mt)
+ : platform(p), identity(id), checksumRequired(false), writingFileDirectory(nullptr), toolNumberAdjust(0), responseMessageType(mt)
{
Init();
}
@@ -25,21 +25,20 @@ void GCodeBuffer::Init()
state = GCodeState::idle;
}
-void GCodeBuffer::Diagnostics()
+void GCodeBuffer::Diagnostics(MessageType mtype)
{
switch (state)
{
case GCodeState::idle:
- platform->MessageF(GENERIC_MESSAGE, "%s is idle\n", identity);
+ platform->MessageF(mtype, "%s is idle\n", identity);
break;
- case GCodeState::executing:
- platform->MessageF(GENERIC_MESSAGE, "%s is doing \"%s\"\n", identity, Buffer());
+ case GCodeState::ready:
+ platform->MessageF(mtype, "%s is ready with \"%s\"\n", identity, Buffer());
break;
- case GCodeState::paused:
- platform->MessageF(GENERIC_MESSAGE, "%s is paused\n", identity);
- break;
+ case GCodeState::executing:
+ platform->MessageF(mtype, "%s is doing \"%s\"\n", identity, Buffer());
}
}
@@ -125,7 +124,7 @@ bool GCodeBuffer::Put(char c)
return false;
}
Init();
- state = GCodeState::executing;
+ state = GCodeState::ready;
return true;
}
else if (!inComment || writingFileDirectory)
@@ -237,7 +236,6 @@ const void GCodeBuffer::GetFloatArray(float a[], size_t& returnedLength)
// Special case if there is one entry and returnedLength requests several.
// Fill the array with the first entry.
-
if (length == 1 && returnedLength > 1)
{
for(size_t i = 1; i < returnedLength; i++)
@@ -361,7 +359,7 @@ long GCodeBuffer::GetLValue()
// Return true if this buffer contains a poll request or empty request that can be executed while macros etc. from another source are being completed
bool GCodeBuffer::IsPollRequest()
{
- if (state == GCodeState::executing)
+ if (state == GCodeState::ready)
{ if (IsEmpty())
{
return true;
diff --git a/src/GCodeBuffer.h b/src/GCodeBuffer.h
index 4b15d6e9..9b403fe3 100644
--- a/src/GCodeBuffer.h
+++ b/src/GCodeBuffer.h
@@ -12,9 +12,9 @@
class GCodeBuffer
{
public:
- GCodeBuffer(Platform* p, const char* id);
+ GCodeBuffer(Platform* p, const char* id, MessageType mt);
void Init(); // Set it up
- void Diagnostics(); // Write some debug info
+ void Diagnostics(MessageType mtype); // Write some debug info
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?
@@ -27,10 +27,10 @@ class GCodeBuffer
const void GetFloatArray(float a[], size_t& length); // Get a :-separated list of floats after a key letter
const void GetLongArray(long l[], size_t& length); // Get a :-separated list of longs after a key letter
const char* Buffer() const;
- bool Active() const;
+ bool IsIdle() const;
+ bool IsReady() const; // Return true if a gcode is ready but hasn't been started yet
+ bool IsExecuting() const; // Return true if a gcode has been started and is not paused
void SetFinished(bool f); // Set the G Code executed (or not)
- void Pause();
- 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; }
@@ -38,12 +38,18 @@ class GCodeBuffer
void SetCommsProperties(uint32_t arg) { checksumRequired = (arg & 1); }
bool StartingNewCode() const { return gcodePointer == 0; }
bool IsPollRequest();
+ MessageType GetResponseMessageType() const { return responseMessageType; }
static bool IsPollCode(int code);
private:
- enum class GCodeState { idle, executing, paused };
+ enum class GCodeState
+ {
+ idle, // we don't have a complete gcode ready
+ ready, // we have a complete gcode but haven't started executing it
+ executing // we have a complete gcode and have started executing it
+ };
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
@@ -55,6 +61,7 @@ class GCodeBuffer
GCodeState 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
+ const MessageType responseMessageType; // The message type we use for responses to commands coming from this channel
};
// Get an Int after a G Code letter
@@ -68,30 +75,24 @@ inline const char* GCodeBuffer::Buffer() const
return gcodeBuffer;
}
-inline bool GCodeBuffer::Active() const
+inline bool GCodeBuffer::IsIdle() const
{
- return state == GCodeState::executing;
+ return state == GCodeState::idle;
}
-inline void GCodeBuffer::SetFinished(bool f)
+inline bool GCodeBuffer::IsReady() const
{
- state = (f) ? GCodeState::idle : GCodeState::executing;
+ return state == GCodeState::ready;
}
-inline void GCodeBuffer::Pause()
+inline bool GCodeBuffer::IsExecuting() const
{
- if (state == GCodeState::executing)
- {
- state = GCodeState::paused;
- }
+ return state == GCodeState::executing;
}
-inline void GCodeBuffer::Resume()
+inline void GCodeBuffer::SetFinished(bool f)
{
- if (state == GCodeState::paused)
- {
- state = GCodeState::executing;
- }
+ state = (f) ? GCodeState::idle : GCodeState::executing;
}
inline const char* GCodeBuffer::WritingFileDirectory() const
diff --git a/src/GCodes.cpp b/src/GCodes.cpp
index be7fa929..fb2ae899 100644
--- a/src/GCodes.cpp
+++ b/src/GCodes.cpp
@@ -25,6 +25,10 @@
#include "RepRapFirmware.h"
+#ifdef DUET_NG
+#include "FirmwareUpdater.h"
+#endif
+
#define DEGREE_SYMBOL "\xC2\xB0" // degree-symbol encoding in UTF8
const char GCodes::axisLetters[AXES] =
@@ -35,12 +39,12 @@ const size_t gcodeReplyLength = 2048; // long enough to pass back a reasonable
GCodes::GCodes(Platform* p, Webserver* w) :
platform(p), webserver(w), active(false), stackPointer(0), auxGCodeReply(nullptr), isFlashing(false)
{
- httpGCode = new GCodeBuffer(platform, "http");
- telnetGCode = new GCodeBuffer(platform, "telnet");
- fileGCode = new GCodeBuffer(platform, "file");
- serialGCode = new GCodeBuffer(platform, "serial");
- auxGCode = new GCodeBuffer(platform, "aux");
- fileMacroGCode = new GCodeBuffer(platform, "macro");
+ httpGCode = new GCodeBuffer(platform, "http", HTTP_MESSAGE);
+ telnetGCode = new GCodeBuffer(platform, "telnet", TELNET_MESSAGE);
+ fileGCode = new GCodeBuffer(platform, "file", GENERIC_MESSAGE);
+ serialGCode = new GCodeBuffer(platform, "serial", HOST_MESSAGE);
+ auxGCode = new GCodeBuffer(platform, "aux", AUX_MESSAGE);
+ fileMacroGCode = new GCodeBuffer(platform, "macro", GENERIC_MESSAGE);
}
void GCodes::Exit()
@@ -52,6 +56,7 @@ void GCodes::Exit()
void GCodes::Init()
{
Reset();
+ firmwareUpdateModuleMap = 0;
distanceScale = 1.0;
rawExtruderTotal = 0.0;
for (size_t extruder = 0; extruder < DRIVES - AXES; extruder++)
@@ -117,16 +122,23 @@ void GCodes::Reset()
feedRate = pausedMoveBuffer[DRIVES] = DEFAULT_FEEDRATE/minutesToSeconds;
ClearMove();
+ for (size_t i =0; i < MaxTriggers; ++i)
+ {
+ triggers[i].Init();
+ }
+ triggersPending = 0;
+
auxDetected = false;
while (auxGCodeReply != nullptr)
{
auxGCodeReply = OutputBuffer::Release(auxGCodeReply);
}
auxSeq = 0;
- simulating = false;
+ simulationMode = 0;
simulationTime = 0.0;
isPaused = false;
filePos = moveBuffer.filePos = noFilePosition;
+ lastEndstopStates = platform->GetAllEndstopStates();
}
float GCodes::FractionOfFilePrinted() const
@@ -144,52 +156,55 @@ float GCodes::FractionOfFilePrinted() const
void GCodes::DoFilePrint(GCodeBuffer* gb, StringRef& reply)
{
- for (int i = 0; i < 50 && fileBeingPrinted.IsLive(); ++i)
+ if (gb != fileGCode || !isPaused)
{
- char b;
- if (fileBeingPrinted.Read(b))
+ for (int i = 0; i < 50 && fileBeingPrinted.IsLive(); ++i)
{
- if (gb->StartingNewCode() && gb == fileGCode)
- {
- filePos = fileBeingPrinted.GetPosition() - 1;
- //debugPrintf("Set file pos %u\n", filePos);
- }
- if (gb->Put(b))
+ char b;
+ if (fileBeingPrinted.Read(b))
{
- gb->SetFinished(ActOnCode(gb, reply));
- break;
- }
- }
- else
- {
- // 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
+ if (gb->StartingNewCode() && gb == fileGCode)
{
- gb->SetFinished(ActOnCode(gb, reply));
+ filePos = fileBeingPrinted.GetPosition() - 1;
+ //debugPrintf("Set file pos %u\n", filePos);
}
- else
+ if (gb->Put(b))
{
- gb->Init();
+ gb->SetFinished(ActOnCode(gb, reply));
+ break;
}
}
- else if (AllMovesAreFinishedAndMoveBufferIsLoaded())
+ else
{
- fileBeingPrinted.Close();
- if (gb == fileGCode)
+ // 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
{
- reprap.GetPrintMonitor()->StoppedPrint();
- if (platform->Emulating() == marlin)
+ if (gb->Put('\n')) // in case there wasn't one ending the file
{
- // Pronterface expects a "Done printing" message
- HandleReply(gb, false, "Done printing file");
+ gb->SetFinished(ActOnCode(gb, reply));
+ }
+ else
+ {
+ gb->Init();
}
}
+ else if (AllMovesAreFinishedAndMoveBufferIsLoaded())
+ {
+ fileBeingPrinted.Close();
+ if (gb == fileGCode)
+ {
+ reprap.GetPrintMonitor()->StoppedPrint();
+ if (platform->Emulating() == marlin)
+ {
+ // Pronterface expects a "Done printing" message
+ HandleReply(gb, false, "Done printing file");
+ }
+ }
+ }
+ break;
}
- break;
}
}
}
@@ -199,369 +214,539 @@ void GCodes::Spin()
if (!active)
return;
+ // First check for new gcodes from all sources except file
+ FillGCodeBuffers();
+
char replyBuffer[gcodeReplyLength];
StringRef reply(replyBuffer, ARRAY_SIZE(replyBuffer));
reply.Clear();
// Check for M105 poll requests from Pronterface and PanelDue so that the status is kept up to date during execution of file macros etc.
- // No need to read multiple characters at a time in this case because the polling rate is quite low.
- if (!serialGCode->Active() && serialGCode->WritingFileDirectory() == nullptr && platform->GCodeAvailable(SerialSource::USB))
+ if (serialGCode->IsReady() && serialGCode->IsPollRequest())
{
- char b = platform->ReadFromSource(SerialSource::USB);
- if (serialGCode->Put(b)) // add char to buffer and test whether the gcode is complete
- {
- if (serialGCode->IsPollRequest())
- {
- serialGCode->SetFinished(ActOnCode(serialGCode, reply));
- return;
- }
- }
+ serialGCode->SetFinished(ActOnCode(serialGCode, reply));
}
-
- if (!auxGCode->Active() && platform->GCodeAvailable(SerialSource::AUX))
+ else if (auxGCode->IsReady() && auxGCode->IsPollRequest())
{
- char b = platform->ReadFromSource(SerialSource::AUX);
- if (auxGCode->Put(b)) // add char to buffer and test whether the gcode is complete
+ auxGCode->SetFinished(ActOnCode(auxGCode, reply));
+ }
+ else
+ {
+ // 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)
{
- auxDetected = true;
- if (auxGCode->IsPollRequest())
+ case GCodeState::normal:
+ StartNextGCode(reply);
+ break;
+
+ case GCodeState::waitingForMoveToComplete:
+ if (AllMovesAreFinishedAndMoveBufferIsLoaded())
{
- auxGCode->SetFinished(ActOnCode(auxGCode, reply));
- return;
+ HandleReply(gbCurrent, false, "");
+ state = GCodeState::normal;
}
- }
- }
-
- // 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;
+ break;
- case GCodeState::waitingForMoveToComplete:
- if (AllMovesAreFinishedAndMoveBufferIsLoaded())
- {
- HandleReply(gbCurrent, 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(gbCurrent, 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(gbCurrent, false, "");
- state = GCodeState::normal;
- }
- break;
+ case GCodeState::setBed1:
+ reprap.GetMove()->SetIdentityTransform();
+ probeCount = 0;
+ state = GCodeState::setBed2;
+ // no break
- case GCodeState::setBed1:
- reprap.GetMove()->SetIdentityTransform();
- probeCount = 0;
- state = GCodeState::setBed2;
- // no break
+ case GCodeState::setBed2:
+ {
+ int numProbePoints = reprap.GetMove()->NumberOfXYProbePoints();
+ if (DoSingleZProbeAtPoint(probeCount, 0.0))
+ {
+ probeCount++;
+ if (probeCount >= numProbePoints)
+ {
+ zProbesSet = true;
+ reprap.GetMove()->FinishedBedProbing(0, reply);
+ HandleReply(gbCurrent, false, reply.Pointer());
+ state = GCodeState::normal;
+ }
+ }
+ }
+ break;
- case GCodeState::setBed2:
- {
- int numProbePoints = reprap.GetMove()->NumberOfXYProbePoints();
- if (DoSingleZProbeAtPoint(probeCount, 0.0))
+ case GCodeState::toolChange1: // Release the old tool (if any)
{
- probeCount++;
- if (probeCount >= numProbePoints)
+ const Tool *oldTool = reprap.GetCurrentTool();
+ if (oldTool != NULL)
{
- zProbesSet = true;
- reprap.GetMove()->FinishedBedProbing(0, reply);
- HandleReply(gbCurrent, false, reply.Pointer());
- state = GCodeState::normal;
+ reprap.StandbyTool(oldTool->Number());
}
}
- }
- break;
+ state = GCodeState::toolChange2;
+ if (reprap.GetTool(newToolNumber) != nullptr && AllAxesAreHomed())
+ {
+ scratchString.printf("tpre%d.g", newToolNumber);
+ DoFileMacro(scratchString.Pointer(), false);
+ }
+ break;
- case GCodeState::toolChange1: // Release the old tool (if any)
- {
- const Tool *oldTool = reprap.GetCurrentTool();
- if (oldTool != NULL)
+ 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) != nullptr && AllAxesAreHomed())
{
- reprap.StandbyTool(oldTool->Number());
+ scratchString.printf("tpost%d.g", newToolNumber);
+ DoFileMacro(scratchString.Pointer(), false);
}
- }
- state = GCodeState::toolChange2;
- if (reprap.GetTool(newToolNumber) != nullptr && AllAxesAreHomed())
- {
- scratchString.printf("tpre%d.g", newToolNumber);
- DoFileMacro(scratchString.Pointer(), false);
- }
- break;
+ 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) != nullptr && AllAxesAreHomed())
- {
- scratchString.printf("tpost%d.g", newToolNumber);
- DoFileMacro(scratchString.Pointer(), false);
- }
- break;
+ case GCodeState::toolChange3:
+ HandleReply(gbCurrent, false, "");
+ state = GCodeState::normal;
+ break;
- case GCodeState::toolChange3:
- HandleReply(gbCurrent, false, "");
- state = GCodeState::normal;
- break;
+ case GCodeState::pausing1:
+ if (AllMovesAreFinishedAndMoveBufferIsLoaded())
+ {
+ state = GCodeState::pausing2;
+ DoFileMacro(PAUSE_G);
+ }
+ break;
- case GCodeState::pausing1:
- if (AllMovesAreFinishedAndMoveBufferIsLoaded())
- {
- state = GCodeState::pausing2;
- DoFileMacro(PAUSE_G);
- }
- break;
+ case GCodeState::pausing2:
+ HandleReply(gbCurrent, false, "Printing paused");
+ state = GCodeState::normal;
+ break;
- case GCodeState::pausing2:
- HandleReply(gbCurrent, false, "Printing paused");
- 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.coords[Z_AXIS];
+ for (size_t drive = 0; drive < AXES; ++drive)
+ {
+ moveBuffer.coords[drive] = pausedMoveBuffer[drive];
+ }
+ for (size_t drive = AXES; drive < DRIVES; ++drive)
+ {
+ moveBuffer.coords[drive] = 0.0;
+ }
+ moveBuffer.feedRate = DEFAULT_FEEDRATE/minutesToSeconds; // ask for a good feed rate, we may have paused during a slow move
+ moveBuffer.moveType = 0;
+ moveBuffer.endStopsToCheck = 0;
+ moveBuffer.usePressureAdvance = false;
+ moveBuffer.filePos = 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.coords[Z_AXIS] = currentZ;
+ state = GCodeState::resuming2;
+ }
+ else
+ {
+ // Just move to the saved position in one go
+ state = GCodeState::resuming3;
+ }
+ moveAvailable = true;
+ }
+ 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.coords[Z_AXIS];
- for (size_t drive = 0; drive < AXES; ++drive)
+ case GCodeState::resuming3:
+ if (AllMovesAreFinishedAndMoveBufferIsLoaded())
{
- moveBuffer.coords[drive] = pausedMoveBuffer[drive];
+ for (size_t i = 0; i < NUM_FANS; ++i)
+ {
+ platform->SetFanValue(i, pausedFanValues[i]);
+ }
+ for (size_t drive = AXES; drive < DRIVES; ++drive)
+ {
+ lastRawExtruderPosition[drive - AXES] = pausedMoveBuffer[drive]; // reset the extruder position in case we are receiving absolute extruder moves
+ }
+ feedRate = pausedMoveBuffer[DRIVES];
+ isPaused = false;
+ HandleReply(gbCurrent, false, "Printing resumed");
+ state = GCodeState::normal;
}
- for (size_t drive = AXES; drive < DRIVES; ++drive)
+ break;
+
+ case GCodeState::flashing1:
+ #ifdef DUET_NG
+ // Update additional modules before the main firmware
+ if (FirmwareUpdater::IsReady())
{
- moveBuffer.coords[drive] = 0.0;
+ bool updating = false;
+ for (unsigned int module = 0; module < NumFirmwareUpdateModules; ++module)
+ {
+ if ((firmwareUpdateModuleMap & (1 << module)) != 0)
+ {
+ firmwareUpdateModuleMap &= ~(1 << module);
+ FirmwareUpdater::UpdateModule(module);
+ updating = true;
+ break;
+ }
+ }
+ if (!updating)
+ {
+ state = GCodeState::flashing2;
+ }
}
- moveBuffer.feedRate = DEFAULT_FEEDRATE/minutesToSeconds; // ask for a good feed rate, we may have paused during a slow move
- moveBuffer.moveType = 0;
- moveBuffer.endStopsToCheck = 0;
- moveBuffer.usePressureAdvance = false;
- moveBuffer.filePos = noFilePosition;
- if (state == GCodeState::resuming1 && currentZ > pausedMoveBuffer[Z_AXIS])
+ #else
+ state = GCodeState::flashing2;
+ #endif
+ break;
+
+ case GCodeState::flashing2:
+ if ((firmwareUpdateModuleMap & 1) != 0)
{
- // First move the head to the correct XY point, then move it down in a separate move
- moveBuffer.coords[Z_AXIS] = currentZ;
- state = GCodeState::resuming2;
+ // Update main firmware
+ firmwareUpdateModuleMap = 0;
+ platform->UpdateFirmware();
+ // The above call does not return unless an error occurred
}
- else
+ isFlashing = false;
+ state = GCodeState::normal;
+ break;
+
+ case GCodeState::stopping: // MO after executing stop.g if present
+ case GCodeState::sleeping: // M1 after executing sleep.g if present
+ // Deselect the active tool and turn off all heaters, unless parameter Hn was used with n > 0
+ if (!gbCurrent->Seen('H') || gbCurrent->GetIValue() <= 0)
{
- // Just move to the saved position in one go
- state = GCodeState::resuming3;
+ Tool* tool = reprap.GetCurrentTool();
+ if (tool != nullptr)
+ {
+ reprap.StandbyTool(tool->Number());
+ }
+ reprap.GetHeat()->SwitchOffAll();
}
- moveAvailable = true;
- }
- break;
- case GCodeState::resuming3:
- if (AllMovesAreFinishedAndMoveBufferIsLoaded())
- {
- for (size_t i = 0; i < NUM_FANS; ++i)
+ // zpl 2014-18-10: Although RRP says M0 is supposed to turn off all drives and heaters,
+ // I think M1 is sufficient for this purpose. Leave M0 for a normal reset.
+ if (state == GCodeState::sleeping)
{
- platform->SetFanValue(i, pausedFanValues[i]);
+ DisableDrives();
}
- fileBeingPrinted.MoveFrom(fileToPrint);
- for (size_t drive = AXES; drive < DRIVES; ++drive)
+ else
{
- lastRawExtruderPosition[drive - AXES] = pausedMoveBuffer[drive]; // reset the extruder position in case we are receiving absolute extruder moves
+ platform->SetDrivesIdle();
}
- feedRate = pausedMoveBuffer[DRIVES];
- fileGCode->Resume();
- isPaused = false;
- HandleReply(gbCurrent, false, "Printing resumed");
+ HandleReply(gbCurrent, false, "");
state = GCodeState::normal;
- }
- break;
+ break;
- default: // should not happen
- break;
+ default: // should not happen
+ break;
+ }
}
+
+ platform->ClassReport(longWait);
}
-void GCodes::StartNextGCode(StringRef& reply)
+// Get new data into the gcode buffers except the file and macro gcode buffers, and deal with any file uploading
+void GCodes::FillGCodeBuffers()
{
- // If a file macro is running, we don't allow anything to interrupt it
- if (doingFileMacro)
+ // Webserver
+ if (httpGCode->IsIdle())
{
- // 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.
- // Note the order establishes a priority: web, serial, queued, file.
- // If file weren't last, then the others would never get a look in when
- // a file was being printed.
- if (!httpGCode->Active() && webserver->GCodeAvailable(WebSource::HTTP))
- {
- int8_t i = 0;
- do
+ for (unsigned int i = 0; i < 16 && webserver->GCodeAvailable(WebSource::HTTP); ++i)
{
char b = webserver->ReadGCode(WebSource::HTTP);
if (httpGCode->Put(b))
{
- // we have a complete gcode
- if (httpGCode->WritingFileDirectory() != NULL)
+ // We have a complete gcode
+ if (httpGCode->WritingFileDirectory() != nullptr)
{
WriteGCodeToFile(httpGCode);
+ httpGCode->SetFinished(true);
}
- else
- {
- httpGCode->SetFinished(ActOnCode(httpGCode, reply));
- }
- break; // stop after receiving a complete gcode in case we haven't finished processing it
+ break;
}
- ++i;
- } while (i < 16 && webserver->GCodeAvailable(WebSource::HTTP));
- platform->ClassReport(longWait);
- return;
+ }
}
// Telnet
- if (!telnetGCode->Active() && webserver->GCodeAvailable(WebSource::Telnet))
+ if (telnetGCode->IsIdle())
{
- size_t i = 0;
- do {
+ for (unsigned int i = 0; i < GCODE_LENGTH && webserver->GCodeAvailable(WebSource::Telnet); ++i)
+ {
char b = webserver->ReadGCode(WebSource::Telnet);
if (telnetGCode->Put(b))
{
- // we have a complete gcode
- telnetGCode->SetFinished(ActOnCode(telnetGCode, reply));
break;
}
- } while (++i < GCODE_LENGTH && webserver->GCodeAvailable(WebSource::Telnet));
+ }
}
- // Now the serial interfaces.
- if (platform->GCodeAvailable(SerialSource::USB))
+ // USB interface
+ if (serialGCode->IsIdle())
{
- // First check the special case of uploading the reprap.htm file
- if (serialGCode->WritingFileDirectory() == platform->GetWebDir())
+ for (unsigned int i = 0; i < 16 && platform->GCodeAvailable(SerialSource::USB); ++i)
{
char b = platform->ReadFromSource(SerialSource::USB);
- WriteHTMLToFile(b, serialGCode);
- platform->ClassReport(longWait);
- return;
- }
-
- // Otherwise just deal in general with incoming bytes from the serial interface
- else if (!serialGCode->Active())
- {
- // Read several bytes instead of just one. This approximately doubles the speed of file uploading.
- int8_t i = 0;
- do
+ // Check the special case of uploading the reprap.htm file
+ if (serialGCode->WritingFileDirectory() == platform->GetWebDir())
+ {
+ WriteHTMLToFile(b, serialGCode);
+ }
+ else if (serialGCode->Put(b)) // add char to buffer and test whether the gcode is complete
{
- char b = platform->ReadFromSource(SerialSource::USB);
- if (serialGCode->Put(b)) // add char to buffer and test whether the gcode is complete
+ // We have a complete gcode
+ if (serialGCode->WritingFileDirectory() != nullptr)
{
- // we have a complete gcode
- if (serialGCode->WritingFileDirectory() != NULL)
- {
- WriteGCodeToFile(serialGCode);
- serialGCode->SetFinished(true);
- }
- else
- {
- serialGCode->SetFinished(ActOnCode(serialGCode, reply));
- }
- break; // stop after receiving a complete gcode in case we haven't finished processing it
+ WriteGCodeToFile(serialGCode);
+ serialGCode->SetFinished(true);
}
- ++i;
- } while (i < 16 && platform->GCodeAvailable(SerialSource::USB));
- platform->ClassReport(longWait);
- return;
+ break;
+ }
}
}
- // Now run the G-Code buffers. It's important to fill up the G-Code buffers before we do this,
- // otherwise we wouldn't have a chance to pause/cancel running prints.
- if (!auxGCode->Active() && platform->GCodeAvailable(SerialSource::AUX))
+ // Aux serial port (typically PanelDue)
+ if (auxGCode->IsIdle())
{
- int8_t i = 0;
- do
+ for (unsigned int i = 0; i < 16 && platform->GCodeAvailable(SerialSource::AUX); ++i)
{
char b = platform->ReadFromSource(SerialSource::AUX);
if (auxGCode->Put(b)) // add char to buffer and test whether the gcode is complete
{
auxDetected = true;
- auxGCode->SetFinished(ActOnCode(auxGCode, reply));
- break; // stop after receiving a complete gcode in case we haven't finished processing it
+ break;
}
- ++i;
- } while (i < 16 && platform->GCodeAvailable(SerialSource::AUX));
+ }
+ }
+}
+
+// Start a new gcode, or continue to execute one that has already been started:
+// 1. If we're doing a file macro, don't allow anything else to interrupt it
+// 2. Continue executing any gcode that we have already started
+// 3. Check for external triggers
+// 4. If we have a gcode ready from any non-file sources, start executing it
+// 5. Else continue a print from file, if one is running
+void GCodes::StartNextGCode(StringRef& reply)
+{
+ // If a file macro is running, we don't allow anything to interrupt it
+ 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->IsReady() || fileMacroGCode->IsExecuting())
+ {
+ 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();
+ }
}
- else if (httpGCode->Active())
+ // Check for gcodes that we have already started
+ else if (httpGCode->IsExecuting())
{
- // Note: Direct web-printing has been dropped, so it's safe to execute web codes immediately
httpGCode->SetFinished(ActOnCode(httpGCode, reply));
}
- else if (serialGCode->Active())
+ else if (telnetGCode->IsExecuting())
+ {
+ telnetGCode->SetFinished(ActOnCode(telnetGCode, reply));
+ }
+ else if (serialGCode->IsExecuting())
{
- // We want codes from the serial interface to be queued unless the print has been paused
serialGCode->SetFinished(ActOnCode(serialGCode, reply));
}
- else if (auxGCode->Active())
+ else if (auxGCode->IsExecuting())
{
- // Same goes for our auxiliary interface
auxGCode->SetFinished(ActOnCode(auxGCode, reply));
}
- else if (fileGCode->Active())
+ else if (fileGCode->IsExecuting())
{
fileGCode->SetFinished(ActOnCode(fileGCode, reply));
}
+ // Check triggers
+ else if (CheckTriggers())
+ {
+ // We've handled a trigger, so nothing else to do
+ }
+ // Check for gcodes we can start
+ else if (httpGCode->IsReady())
+ {
+ httpGCode->SetFinished(ActOnCode(httpGCode, reply));
+ }
+ else if (telnetGCode->IsReady())
+ {
+ telnetGCode->SetFinished(ActOnCode(telnetGCode, reply));
+ }
+ else if (serialGCode->IsReady())
+ {
+ serialGCode->SetFinished(ActOnCode(serialGCode, reply));
+ }
+ else if (auxGCode->IsReady())
+ {
+ auxGCode->SetFinished(ActOnCode(auxGCode, reply));
+ }
+ // Print some more of the current file
else
{
- DoFilePrint(fileGCode, reply); // else see if there is anything to print from file
+ DoFilePrint(fileGCode, reply);
}
+}
- platform->ClassReport(longWait);
+// Check for and execute triggers, returning true if started executing one.
+// We already checked that no file macro is being executed before calling this.
+bool GCodes::CheckTriggers()
+{
+ // Check for endstop state changes that activate new triggers
+ const TriggerMask oldEndstopStates = lastEndstopStates;
+ lastEndstopStates = platform->GetAllEndstopStates();
+ const TriggerMask risen = lastEndstopStates & ~oldEndstopStates,
+ fallen = ~lastEndstopStates & oldEndstopStates;
+ unsigned int lowestTriggerPending = MaxTriggers;
+ for (unsigned int triggerNumber = 0; triggerNumber < MaxTriggers; ++triggerNumber)
+ {
+ if ((triggers[triggerNumber].rising & risen) != 0 || (triggers[triggerNumber].falling & fallen) != 0)
+ {
+ triggersPending |= (1 << triggerNumber);
+ }
+ if (triggerNumber < lowestTriggerPending && (triggersPending & (1 << triggerNumber)) != 0)
+ {
+ lowestTriggerPending = triggerNumber;
+ }
+ }
+
+ // If any triggers are pending, activate the one with the lowest number
+ if (lowestTriggerPending < MaxTriggers)
+ {
+ gbCurrent = nullptr;
+ triggersPending &= ~(1 << lowestTriggerPending); // clear the trigger
+
+ // Execute the trigger
+ switch(lowestTriggerPending)
+ {
+ case 0:
+ // Trigger 0 does an emergency stop
+ DoEmergencyStop();
+ break;
+
+ case 1:
+ // Trigger 1 pauses the print, if printing from file
+ if (!isPaused && reprap.GetPrintMonitor()->IsPrinting())
+ {
+ DoPause(true);
+ }
+ break;
+
+ default:
+ // All other trigger numbers execute the corresponding macro file
+ {
+ char buffer[25];
+ StringRef filename(buffer, ARRAY_SIZE(buffer));
+ filename.printf(SYS_DIR "trigger%u.g", lowestTriggerPending);
+ DoFileMacro(filename.Pointer(), true);
+ }
+ }
+ return true; // we processed a trigger
+ }
+ return false; // no triggers were pending
+}
+
+// Execute an emergency stop
+void GCodes::DoEmergencyStop()
+{
+ reprap.EmergencyStop();
+ Reset();
+ platform->Message(GENERIC_MESSAGE, "Emergency Stop! Reset the controller to continue.");
+}
+
+// Pause the print. Before calling this, check that we are doing a file print that isn't already paused.
+void GCodes::DoPause(bool externalToFile)
+{
+ if (externalToFile)
+ {
+ // Pausing a file print via another input source
+ pausedMoveBuffer[DRIVES] = feedRate; // the call to PausePrint may or may not change this
+ FilePosition fPos = reprap.GetMove()->PausePrint(pausedMoveBuffer); // tell Move we wish to pause the current print
+ FileData& fdata = (stackPointer == 0) ? fileBeingPrinted : stack[0].fileState;
+ if (fPos != noFilePosition && fdata.IsLive())
+ {
+ fdata.Seek(fPos); // replay the abandoned instructions if/when we resume
+ }
+ fileGCode->Init();
+ if (moveAvailable)
+ {
+ for (size_t drive = AXES; drive < DRIVES; ++drive)
+ {
+ pausedMoveBuffer[drive] += moveBuffer.coords[drive]; // add on the extrusion in the move not yet taken
+ }
+ ClearMove();
+ }
+
+ for (size_t drive = AXES; drive < DRIVES; ++drive)
+ {
+ pausedMoveBuffer[drive] = lastRawExtruderPosition[drive - AXES] - pausedMoveBuffer[drive];
+ }
+
+ if (reprap.Debug(moduleGcodes))
+ {
+ platform->MessageF(GENERIC_MESSAGE, "Paused print, file offset=%u\n", fPos);
+ }
+ }
+ else
+ {
+ // Pausing a file print because of a command in the file itself
+ for (size_t drive = 0; drive < AXES; ++drive)
+ {
+ pausedMoveBuffer[drive] = moveBuffer.coords[drive];
+ }
+ for (size_t drive = AXES; drive < DRIVES; ++drive)
+ {
+ pausedMoveBuffer[drive] = lastRawExtruderPosition[drive - AXES]; // get current extruder positions into pausedMoveBuffer
+ }
+ pausedMoveBuffer[DRIVES] = feedRate;
+ }
+
+ for (size_t i = 0; i < NUM_FANS; ++i)
+ {
+ pausedFanValues[i] = platform->GetFanValue(i);
+ }
+ state = GCodeState::pausing1;
+ isPaused = true;
}
-void GCodes::Diagnostics()
+void GCodes::Diagnostics(MessageType mtype)
{
- platform->Message(GENERIC_MESSAGE, "GCodes Diagnostics:\n");
- platform->MessageF(GENERIC_MESSAGE, "Move available? %s\n", moveAvailable ? "yes" : "no");
- platform->MessageF(GENERIC_MESSAGE, "Stack pointer: %u of %u\n", stackPointer, StackSize);
-
- fileMacroGCode->Diagnostics();
- httpGCode->Diagnostics();
- telnetGCode->Diagnostics();
- serialGCode->Diagnostics();
- auxGCode->Diagnostics();
- fileGCode->Diagnostics();
+ platform->Message(mtype, "GCodes Diagnostics:\n");
+ platform->MessageF(mtype, "Move available? %s\n", moveAvailable ? "yes" : "no");
+ platform->MessageF(mtype, "Stack pointer: %u of %u\n", stackPointer, StackSize);
+
+ fileMacroGCode->Diagnostics(mtype);
+ httpGCode->Diagnostics(mtype);
+ telnetGCode->Diagnostics(mtype);
+ serialGCode->Diagnostics(mtype);
+ auxGCode->Diagnostics(mtype);
+ fileGCode->Diagnostics(mtype);
}
// The wait till everything's done function. If you need the machine to
@@ -876,7 +1061,7 @@ void GCodes::ClearMove()
bool GCodes::DoFileMacro(const char* fileName, bool reportMissing)
{
FileStore *f = platform->GetFileStore(platform->GetSysDir(), fileName, false);
- if (f == NULL)
+ if (f == nullptr)
{
if (reportMissing)
{
@@ -1620,7 +1805,7 @@ bool GCodes::DoDwell(GCodeBuffer *gb)
float dwell = 0.001 * (float) gb->GetLValue(); // P values are in milliseconds; we need seconds
- if (simulating)
+ if (simulationMode != 0)
{
simulationTime += dwell;
return true;
@@ -1715,7 +1900,7 @@ void GCodes::SetOrReportOffsets(StringRef& reply, GCodeBuffer *gb)
settingTemps = true;
}
- if (settingTemps && !simulating)
+ if (settingTemps && simulationMode == 0)
{
tool->SetVariables(standby, active);
}
@@ -1929,10 +2114,12 @@ bool GCodes::ChangeMicrostepping(size_t drive, int microsteps, int mode) const
// Handle sending a reply back to the appropriate interface(s).
// Note that 'reply' may be empty. If it isn't, then we need to append newline when sending it.
+// Also, gb may be null if we were executing a trigger macro.
void GCodes::HandleReply(GCodeBuffer *gb, bool error, const char* reply)
{
// Don't report "ok" responses if a (macro) file is being processed
- if ((gb == fileMacroGCode || gb == fileGCode) && reply[0] == 0)
+ // Also check that this response was triggered by a gcode
+ if (gb == nullptr || ((gb == fileMacroGCode || gb == fileGCode) && reply[0] == 0))
{
return;
}
@@ -2048,7 +2235,7 @@ void GCodes::HandleReply(GCodeBuffer *gb, bool error, const char* reply)
void GCodes::HandleReply(GCodeBuffer *gb, bool error, OutputBuffer *reply)
{
// Although unlikely, it's possible that we get a nullptr reply. Don't proceed if this is the case
- if (reply == nullptr)
+ if (gb == nullptr || reply == nullptr)
{
return;
}
@@ -2427,7 +2614,7 @@ bool GCodes::HandleGcode(GCodeBuffer* gb, StringRef& reply)
bool error = false;
int code = gb->GetIValue();
- if (simulating && code != 0 && code != 1 && code != 4 && code != 10 && code != 20 && code != 21 && code != 90 && code != 91 && code != 92)
+ if (simulationMode != 0 && code != 0 && code != 1 && code != 4 && code != 10 && code != 20 && code != 21 && code != 90 && code != 91 && code != 92)
{
return true; // we only simulate some gcodes
}
@@ -2582,7 +2769,7 @@ bool GCodes::HandleMcode(GCodeBuffer* gb, StringRef& reply)
bool error = false;
int code = gb->GetIValue();
- if (simulating && (code < 20 || code > 37) && code != 82 && code != 83 && code != 111 && code != 105 && code != 122 && code != 408 && code != 999)
+ if (simulationMode != 0 && (code < 20 || code > 37) && code != 82 && code != 83 && code != 111 && code != 105 && code != 122 && code != 408 && code != 999)
{
return true; // we don't yet simulate most M codes
}
@@ -2603,7 +2790,7 @@ bool GCodes::HandleMcode(GCodeBuffer* gb, StringRef& reply)
{
isPaused = false;
reply.copy("Print cancelled");
- // If we are cancelling a paused print with M0 and cancel.g exists then run it
+ // If we are cancelling a paused print with M0 and cancel.g exists then run it and do nothing else
if (code == 0)
{
if (DoFileMacro(CANCEL_G, false))
@@ -2613,28 +2800,8 @@ bool GCodes::HandleMcode(GCodeBuffer* gb, StringRef& reply)
}
}
- // Otherwise, deselect the active tool, if any
- {
- Tool* tool = reprap.GetCurrentTool();
- if (tool != nullptr)
- {
- reprap.StandbyTool(tool->Number());
- }
- }
-
- // Turn the heaters off
- reprap.GetHeat()->SwitchOffAll();
-
- // zpl 2014-18-10: Although RRP says M0 is supposed to turn off all drives and heaters,
- // I think M1 is sufficient for this purpose. Leave M0 for a normal reset.
- if (code == 1)
- {
- DisableDrives();
- }
- else
- {
- platform->SetDrivesIdle();
- }
+ state = (code == 0) ? GCodeState::stopping : GCodeState::sleeping;
+ DoFileMacro((code == 0) ? STOP_G : SLEEP_G, false);
break;
#if SUPPORT_ROLAND
@@ -2819,17 +2986,16 @@ bool GCodes::HandleMcode(GCodeBuffer* gb, StringRef& reply)
return false;
}
- if (!fileToPrint.IsLive())
- {
- reply.copy("Cannot print, because no file is selected!");
- error = true;
- }
- else if (isPaused)
+ if (isPaused)
{
- fileGCode->Resume();
state = GCodeState::resuming1;
DoFileMacro(RESUME_G);
}
+ else if (!fileToPrint.IsLive())
+ {
+ reply.copy("Cannot print, because no file is selected!");
+ error = true;
+ }
else
{
fileBeingPrinted.MoveFrom(fileToPrint);
@@ -2853,64 +3019,14 @@ bool GCodes::HandleMcode(GCodeBuffer* gb, StringRef& reply)
reply.copy("Cannot pause print, because no file is being printed!");
error = true;
}
- else if (doingFileMacro)
+ else if (doingFileMacro && gb != fileMacroGCode)
{
reply.copy("Cannot pause macro files, wait for it to complete first!");
error = true;
}
else
{
- if (code == 25)
- {
- // Pausing a print via another input source
- pausedMoveBuffer[DRIVES] = feedRate; // the call to PausePrint may or may not change this
- FilePosition fPos = reprap.GetMove()->PausePrint(pausedMoveBuffer); // tell Move we wish to pause the current print
- if (fPos != noFilePosition && fileBeingPrinted.IsLive())
- {
- fileBeingPrinted.Seek(fPos); // replay the abandoned instructions if/when we resume
- }
- fileGCode->Init();
- if (moveAvailable)
- {
- for (size_t drive = AXES; drive < DRIVES; ++drive)
- {
- pausedMoveBuffer[drive] += moveBuffer.coords[drive]; // add on the extrusion in the move not yet taken
- }
- ClearMove();
- }
-
- for (size_t drive = AXES; drive < DRIVES; ++drive)
- {
- pausedMoveBuffer[drive] = lastRawExtruderPosition[drive - AXES] - pausedMoveBuffer[drive];
- }
-
- if (reprap.Debug(moduleGcodes))
- {
- platform->MessageF(GENERIC_MESSAGE, "Paused print, file offset=%u\n", fPos);
- }
- }
- else
- {
- // Pausing a file print because of a command in the file itself
- for (size_t drive = 0; drive < AXES; ++drive)
- {
- pausedMoveBuffer[drive] = moveBuffer.coords[drive];
- }
- for (size_t drive = AXES; drive < DRIVES; ++drive)
- {
- pausedMoveBuffer[drive] = lastRawExtruderPosition[drive - AXES]; // get current extruder positions into pausedMoveBuffer
- }
- pausedMoveBuffer[DRIVES] = feedRate;
- }
-
- for (size_t i = 0; i < NUM_FANS; ++i)
- {
- pausedFanValues[i] = platform->GetFanValue(i);
- }
- fileToPrint.MoveFrom(fileBeingPrinted);
- fileGCode->Pause();
- state = GCodeState::pausing1;
- isPaused = true;
+ DoPause(code == 25 && gb != fileGCode);
}
break;
@@ -3021,11 +3137,11 @@ bool GCodes::HandleMcode(GCodeBuffer* gb, StringRef& reply)
return false;
}
- bool wasSimulating = simulating;
- simulating = gb->GetIValue() != 0;
- reprap.GetMove()->Simulate(simulating);
+ bool wasSimulating = (simulationMode != 0);
+ simulationMode = (uint8_t)gb->GetIValue();
+ reprap.GetMove()->Simulate(simulationMode);
- if (simulating)
+ if (simulationMode != 0)
{
simulationTime = 0.0;
if (!wasSimulating)
@@ -3048,7 +3164,7 @@ bool GCodes::HandleMcode(GCodeBuffer* gb, StringRef& reply)
else
{
reply.printf("Simulation mode: %s, move time: %.1f sec, other time: %.1f sec",
- (simulating) ? "on" : "off", simulationTime, reprap.GetMove()->GetSimulationTime());
+ (simulationMode != 0) ? "on" : "off", simulationTime, reprap.GetMove()->GetSimulationTime());
}
break;
@@ -3357,6 +3473,11 @@ bool GCodes::HandleMcode(GCodeBuffer* gb, StringRef& reply)
else
{
tool = reprap.GetCurrentTool();
+ // If no tool is selected, and there is only one tool, set the active temperature for that one
+ if (tool == nullptr)
+ {
+ tool = reprap.GetOnlyTool();
+ }
}
SetToolHeaters(tool, temperature);
result = ToolHeatersAtSetTemperatures(tool);
@@ -3386,9 +3507,7 @@ bool GCodes::HandleMcode(GCodeBuffer* gb, StringRef& reply)
break;
case 112: // Emergency stop - acted upon in Webserver, but also here in case it comes from USB etc.
- reprap.EmergencyStop();
- Reset();
- reply.copy("Emergency Stop! Reset the controller to continue.");
+ DoEmergencyStop();
break;
case 114: // Deprecated
@@ -3504,7 +3623,7 @@ bool GCodes::HandleMcode(GCodeBuffer* gb, StringRef& reply)
int val = (gb->Seen('P')) ? gb->GetIValue() : 0;
if (val == 0)
{
- reprap.Diagnostics();
+ reprap.Diagnostics(gb->GetResponseMessageType());
}
else
{
@@ -3932,13 +4051,10 @@ bool GCodes::HandleMcode(GCodeBuffer* gb, StringRef& reply)
// For case 226, see case 25
case 300: // Beep
- if (gb->Seen('P'))
{
- int ms = gb->GetIValue();
- if (gb->Seen('S'))
- {
- reprap.Beep(gb->GetIValue(), ms);
- }
+ int ms = (gb->Seen('P')) ? gb->GetIValue() : 1000; // time in milliseconds
+ int freq = (gb->Seen('S')) ? gb->GetIValue() : 4600; // 4600Hz produces the loudest sound on a PanelDue
+ reprap.Beep(freq, ms);
}
break;
@@ -4887,6 +5003,87 @@ bool GCodes::HandleMcode(GCodeBuffer* gb, StringRef& reply)
break;
#endif
+ case 581: // Configure external trigger
+ case 582: // Check external trigger
+ if (gb->Seen('T'))
+ {
+ unsigned int triggerNumber = gb->GetIValue();
+ if (triggerNumber < MaxTriggers)
+ {
+ if (code == 582)
+ {
+ uint32_t states = platform->GetAllEndstopStates();
+ if ((triggers[triggerNumber].rising & states) != 0 || (triggers[triggerNumber].falling & ~states) != 0)
+ {
+ triggersPending |= (1 << triggerNumber);
+ }
+ }
+ else if (gb->Seen('S'))
+ {
+ int sval = gb->GetIValue();
+ TriggerMask triggerMask = 0;
+ for (size_t axis = 0; axis < AXES; ++axis)
+ {
+ if (gb->Seen(axisLetters[axis]))
+ {
+ triggerMask |= (1u << axis);
+ }
+ }
+ if (gb->Seen(extrudeLetter))
+ {
+ long eStops[DRIVES - AXES];
+ size_t numEntries = DRIVES - AXES;
+ gb->GetLongArray(eStops, numEntries);
+ for (size_t i = 0; i < numEntries; ++i)
+ {
+ if (eStops[i] >= 0 && (unsigned long)eStops[i] < DRIVES - AXES)
+ {
+ triggerMask |= (1u << (eStops[i] + AXES));
+ }
+ }
+ }
+ switch(sval)
+ {
+ case -1:
+ if (triggerMask == 0)
+ {
+ triggers[triggerNumber].rising = triggers[triggerNumber].falling = 0;
+ }
+ else
+ {
+ triggers[triggerNumber].rising &= (~triggerMask);
+ triggers[triggerNumber].falling &= (~triggerMask);
+ }
+ break;
+
+ case 0:
+ triggers[triggerNumber].falling |= triggerMask;
+ break;
+
+ case 1:
+ triggers[triggerNumber].rising |= triggerMask;
+ break;
+
+ default:
+ platform->Message(GENERIC_MESSAGE, "Bad S parameter in M581 command\n");
+ }
+ }
+ else
+ {
+ reply.printf("Trigger %u fires on a rising edge on ", triggerNumber);
+ ListTriggers(reply, triggers[triggerNumber].rising);
+ reply.cat(" or a falling edge on ");
+ ListTriggers(reply, triggers[triggerNumber].falling);
+ reply.cat(" endstop inputs");
+ }
+ }
+ else
+ {
+ platform->Message(GENERIC_MESSAGE, "Trigger number out of range\n");
+ }
+ }
+ break;
+
case 665: // Set delta configuration
if (!AllMovesAreFinishedAndMoveBufferIsLoaded())
{
@@ -5104,46 +5301,62 @@ bool GCodes::HandleMcode(GCodeBuffer* gb, StringRef& reply)
break;
case 997: // Perform firmware update
+ if (firmwareUpdateModuleMap == 0) // have we worked out which modules to update?
{
- int sparam = 0; // default to zero for compatibility with the original implementation
+ // Find out which modules we have been asked to update
+ long modulesToUpdate[3];
+ size_t numUpdateModules;
if (gb->Seen('S'))
{
- sparam = gb->GetIValue();
+ numUpdateModules = ARRAY_SIZE(modulesToUpdate);
+ gb->GetLongArray(modulesToUpdate, numUpdateModules);
}
- if (sparam == 0)
+ else
{
- // Update main firmware
- if (!platform->GetMassStorage()->FileExists(platform->GetSysDir(), IAP_FIRMWARE_FILE))
- {
- platform->MessageF(GENERIC_MESSAGE, "Error: Firmware file \"%s\" not found in sys directory\n", IAP_FIRMWARE_FILE);
- break;
- }
- if (!platform->GetMassStorage()->FileExists(platform->GetSysDir(), IAP_UPDATE_FILE))
- {
- platform->MessageF(GENERIC_MESSAGE, "Error: IAP file \"%s\" not found in sys directory\n", IAP_UPDATE_FILE);
- break;
- }
+ numUpdateModules = 0;
+ }
- isFlashing = true;
- if (!DoDwellTime(1.0))
+ if (numUpdateModules == 0)
+ {
+ firmwareUpdateModuleMap = (1 << 0); // no modules specified, so update module 0 to match old behaviour
+ }
+ else
+ {
+ for (size_t i = 0; i < numUpdateModules; ++i)
{
- // wait a second so all HTTP clients are notified
- return false;
+ long t = modulesToUpdate[i];
+ if (t < 0 || (unsigned long)t >= NumFirmwareUpdateModules)
+ {
+ platform->MessageF(GENERIC_MESSAGE, "Invalid module number '%ld'\n", t);
+ firmwareUpdateModuleMap = 0;
+ break;
+ }
+ firmwareUpdateModuleMap |= (1 << t);
}
- platform->UpdateFirmware();
- isFlashing = false; // should never get here, but leave this here in case an error has occurred
}
+
+ // Check prerequisites of all modules to be updated, if any are not met then don't update any of them
#ifdef DUET_NG
- else if (sparam >= 1 && sparam <= 3)
+ if (!FirmwareUpdater::CheckFirmwareUpdatePrerequisites(firmwareUpdateModuleMap))
{
- reprap.GetNetwork()->FirmwareUpdate(sparam);
+ break;
}
#endif
- else
+ if ((firmwareUpdateModuleMap & 1) != 0 && !platform->CheckFirmwareUpdatePrerequisites())
{
- reply.copy("Error: M997 invalid S parameter");
+ break;
}
}
+
+ // If we get here then we have the module map, and all prerequisites are satisfied
+ reprap.GetHeat()->SwitchOffAll(); // turn all heaters off because the main loop may get suspended
+ isFlashing = true; // this tells the web interface and PanelDue that we are about to flash firmware
+ if (!DoDwellTime(1.0)) // wait a second so all HTTP clients are notified
+ {
+ return false;
+ }
+
+ state = GCodeState::flashing1;
break;
case 998:
@@ -5195,7 +5408,7 @@ bool GCodes::HandleTcode(GCodeBuffer* gb, StringRef& reply)
newToolNumber = gb->GetIValue();
newToolNumber += gb->GetToolNumberAdjust();
- if (simulating) // we don't yet simulate any T codes
+ if (simulationMode != 0) // we don't yet simulate any T codes
{
HandleReply(gb, false, "");
}
@@ -5224,16 +5437,6 @@ float GCodes::GetRawExtruderTotalByDrive(size_t extruder) const
return (extruder < (DRIVES - AXES)) ? rawExtruderTotalByDrive[extruder] : 0.0;
}
-// Pause the current SD card print. Called from the web interface.
-void GCodes::PauseSDPrint()
-{
- if (fileBeingPrinted.IsLive())
- {
- fileToPrint.MoveFrom(fileBeingPrinted);
- fileGCode->Pause(); // if we are executing some sort of wait command, pause it until we restart
- }
-}
-
// Cancel the current SD card print
void GCodes::CancelPrint()
{
@@ -5316,4 +5519,36 @@ const char *GCodes::TranslateEndStopResult(EndStopHit es)
}
}
+// Append a list of trigger endstops to a message
+void GCodes::ListTriggers(StringRef reply, TriggerMask mask)
+{
+ if (mask == 0)
+ {
+ reply.cat("(none)");
+ }
+ else
+ {
+ bool printed = false;
+ for (unsigned int i = 0; i < DRIVES; ++i)
+ {
+ if ((mask & (1 << i)) != 0)
+ {
+ if (printed)
+ {
+ reply.cat(' ');
+ }
+ if (i < AXES)
+ {
+ reply.cat(axisLetters[i]);
+ }
+ else
+ {
+ reply.catf("E%d", i - AXES);
+ }
+ printed = true;
+ }
+ }
+ }
+}
+
// End
diff --git a/src/GCodes.h b/src/GCodes.h
index 800e9ce9..c7f3c5fd 100644
--- a/src/GCodes.h
+++ b/src/GCodes.h
@@ -52,7 +52,11 @@ enum class GCodeState
pausing2,
resuming1,
resuming2,
- resuming3
+ resuming3,
+ flashing1,
+ flashing2,
+ stopping,
+ sleeping
};
// Small class to stack the state when we execute a macro file
@@ -68,6 +72,19 @@ public:
bool doingFileMacro;
};
+typedef uint16_t TriggerMask;
+
+struct Trigger
+{
+ TriggerMask rising;
+ TriggerMask falling;
+
+ void Init()
+ {
+ rising = falling = 0;
+ }
+};
+
//****************************************************************************************************
// The GCode interpreter
@@ -99,13 +116,12 @@ public:
void GetCurrentCoordinates(StringRef& s) const; // Write where we are into a string
bool DoingFileMacro() const; // Or still busy processing a macro file?
float FractionOfFilePrinted() const; // Get fraction of file printed
- void Diagnostics(); // Send helpful information out
+ void Diagnostics(MessageType mtype); // Send helpful information out
bool HaveIncomingData() const; // Is there something that we have to do?
size_t GetStackPointer() const; // Returns the current stack pointer
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
- void PauseSDPrint(); // Pause the current print from SD card
float GetSpeedFactor() const { return speedFactor * minutesToSeconds; } // Return the current speed factor
float GetExtrusionFactor(size_t extruder) { return extrusionFactors[extruder]; } // Return the current extrusion factors
float GetRawExtruderPosition(size_t drive) const; // Get the actual extruder position, after adjusting the extrusion factor
@@ -127,6 +143,7 @@ public:
private:
+ void FillGCodeBuffers(); // Get new data into the gcode buffers
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
@@ -175,6 +192,10 @@ private:
const char *TranslateEndStopResult(EndStopHit es); // Translate end stop result to text
bool RetractFilament(bool retract); // Retract or un-retract filaments
bool ChangeMicrostepping(size_t drive, int microsteps, int mode) const; // Change microstepping on the specified drive
+ void ListTriggers(StringRef reply, TriggerMask mask); // Append a list of trigger endstops to a message
+ bool CheckTriggers(); // Check for and execute triggers
+ void DoEmergencyStop(); // Execute an emergency stop
+ void DoPause(bool externalToFile); // Pause the print
Platform* platform; // The RepRap machine
Webserver* webserver; // The webserver class
@@ -234,8 +255,8 @@ private:
bool auxDetected; // Have we processed at least one G-Code from an AUX device?
OutputBuffer *auxGCodeReply; // G-Code reply for AUX devices (special one because it is actually encapsulated before sending)
uint32_t auxSeq; // Sequence number for AUX devices
- bool simulating;
- float simulationTime;
+ float simulationTime; // Accumulated simulation time
+ uint8_t simulationMode; // 0 = not simulating, 1 = simulating, >1 are simulation modes for debugging
bool isFlashing; // Is a new firmware binary going to be flashed?
FilePosition filePos; // The position we got up to in the file being printed
@@ -243,6 +264,15 @@ private:
float retractLength, retractExtra; // retraction length and extra length to un-retract
float retractSpeed; // retract speed in mm/min
float retractHop; // Z hop when retracting
+
+ // Triggers
+ Trigger triggers[MaxTriggers]; // Trigger conditions
+ TriggerMask lastEndstopStates; // States of the endstop inputs last time we looked
+ static_assert(MaxTriggers <= 32, "Too many triggers");
+ uint32_t triggersPending; // Bitmap of triggers pending but not yet executed
+
+ // Firmware update
+ uint8_t firmwareUpdateModuleMap; // Bitmap of firmware modules to be updated
};
//*****************************************************************************************************
diff --git a/src/Heat.cpp b/src/Heat.cpp
index 3be29da2..f7de96c1 100644
--- a/src/Heat.cpp
+++ b/src/Heat.cpp
@@ -69,14 +69,14 @@ void Heat::Spin()
platform->ClassReport(longWait);
}
-void Heat::Diagnostics()
+void Heat::Diagnostics(MessageType mtype)
{
- platform->Message(GENERIC_MESSAGE, "Heat Diagnostics:\n");
+ platform->Message(mtype, "Heat Diagnostics:\n");
for (size_t heater=0; heater < HEATERS; heater++)
{
if (pids[heater]->Active())
{
- platform->MessageF(GENERIC_MESSAGE, "Heater %d: I-accumulator = %.1f\n", heater, pids[heater]->GetAccumulator());
+ platform->MessageF(mtype, "Heater %d: I-accumulator = %.1f\n", heater, pids[heater]->GetAccumulator());
}
}
}
diff --git a/src/Heat.h b/src/Heat.h
index c68e4523..30c58ba7 100644
--- a/src/Heat.h
+++ b/src/Heat.h
@@ -108,7 +108,7 @@ class Heat
void ResetFault(int8_t heater); // Reset a heater fault - only call this if you know what you are doing
bool AllHeatersAtSetTemperatures(bool includingBed) const; // Is everything at temperature within tolerance?
bool HeaterAtSetTemperature(int8_t heater) const; // Is a specific heater at temperature within tolerance?
- void Diagnostics(); // Output useful information
+ void Diagnostics(MessageType mtype); // Output useful information
float GetAveragePWM(int8_t heater) const; // Return the running average PWM to the heater as a fraction in [0, 1].
bool UseSlowPwm(int8_t heater) const; // Queried by the Platform class
diff --git a/src/Libraries/Flash/DueFlashStorage.h b/src/Libraries/Flash/DueFlashStorage.h
index c93f11a9..cfec9c19 100644
--- a/src/Libraries/Flash/DueFlashStorage.h
+++ b/src/Libraries/Flash/DueFlashStorage.h
@@ -15,7 +15,7 @@ Further modified up by David Crocker
#ifndef DUEFLASHSTORAGE_H
#define DUEFLASHSTORAGE_H
-#include <Arduino.h>
+#include "Core.h"
#include "flash_efc.h"
#ifdef DUET_NG
diff --git a/src/Libraries/TemperatureSensor/TemperatureSensor.h b/src/Libraries/TemperatureSensor/TemperatureSensor.h
index 37b64a3b..d29f6f74 100644
--- a/src/Libraries/TemperatureSensor/TemperatureSensor.h
+++ b/src/Libraries/TemperatureSensor/TemperatureSensor.h
@@ -2,7 +2,7 @@
#define TEMPERATURESENSOR_H
#include "TemperatureError.h" // for result codes
-#include "Arduino.h"
+#include "Core.h"
#include "SharedSpi.h" // for sspi_device
class TemperatureSensor
diff --git a/src/MessageType.h b/src/MessageType.h
new file mode 100644
index 00000000..4420031c
--- /dev/null
+++ b/src/MessageType.h
@@ -0,0 +1,24 @@
+/*
+ * MessageType.h
+ *
+ * Created on: 21 May 2016
+ * Author: David
+ */
+
+#ifndef MESSAGETYPE_H_
+#define MESSAGETYPE_H_
+
+// Supported message destinations
+enum MessageType
+{
+ AUX_MESSAGE, // A message that is to be sent to the panel
+ AUX2_MESSAGE, // A message that is to be sent to the second auxiliary device
+ HOST_MESSAGE, // A message that is to be sent in non-blocking mode to the host via USB
+ DEBUG_MESSAGE, // A debug message to send in blocking mode to USB
+ HTTP_MESSAGE, // A message that is to be sent to the web (HTTP)
+ TELNET_MESSAGE, // A message that is to be sent to a Telnet client
+ GENERIC_MESSAGE, // A message that is to be sent to the web, USB and panel
+ FIRMWARE_UPDATE_MESSAGE // A message that conveys progress of a firmware update
+};
+
+#endif /* MESSAGETYPE_H_ */
diff --git a/src/Move.cpp b/src/Move.cpp
index 9dbb2e75..fcefdfdc 100644
--- a/src/Move.cpp
+++ b/src/Move.cpp
@@ -47,6 +47,7 @@ void Move::Init()
currentDda = nullptr;
addNoMoreMoves = false;
stepErrors = 0;
+ numLookaheadUnderruns = 0;
// Clear the transforms
SetIdentityTransform();
@@ -84,7 +85,7 @@ void Move::Init()
iState = IdleState::idle;
idleCount = 0;
- simulating = false;
+ simulationMode = 0;
simulationTime = 0.0;
active = true;
@@ -120,7 +121,10 @@ void Move::Spin()
++stepErrors;
reprap.GetPlatform()->LogError(ErrorCode::BadMove);
}
- ddaRingCheckPointer->Free();
+ if (ddaRingCheckPointer->Free())
+ {
+ ++numLookaheadUnderruns;
+ }
ddaRingCheckPointer = ddaRingCheckPointer->GetNext();
}
@@ -152,50 +156,53 @@ void Move::Spin()
if (reprap.GetGCodes()->ReadMove(nextMove))
{
// We have a new move
+ if (simulationMode < 2) // in simulation mode 2 and higher, we don't process incoming moves beyond this point
+ {
#if 0 //*** This code is not finished yet ***
- // If we are doing bed compensation and the move crosses a compensation boundary by a significant amount,
- // segment it so that we can apply proper bed compensation
- // Issues here:
- // 1. Are there enough DDAs? need to make nextMove static and remember whether we have the remains of a move in there.
- // 2. Pause/restart: if we restart a segmented move when we have already executed part of it, we will extrude too much.
- // Perhaps remember how much of the last move we executed? Or always insist on completing all the segments in a move?
- bool isSegmented;
- do
- {
- GCodes::RawMove tempMove = nextMove;
- isSegmented = SegmentMove(tempMove);
- if (isSegmented)
+ // If we are doing bed compensation and the move crosses a compensation boundary by a significant amount,
+ // segment it so that we can apply proper bed compensation
+ // Issues here:
+ // 1. Are there enough DDAs? need to make nextMove static and remember whether we have the remains of a move in there.
+ // 2. Pause/restart: if we restart a segmented move when we have already executed part of it, we will extrude too much.
+ // Perhaps remember how much of the last move we executed? Or always insist on completing all the segments in a move?
+ bool isSegmented;
+ do
{
- // Extruder moves are relative, so we need to adjust the extrusion amounts in the original move
- for (size_t drive = AXES; drive < DRIVES; ++drive)
+ GCodes::RawMove tempMove = nextMove;
+ isSegmented = SegmentMove(tempMove);
+ if (isSegmented)
{
- nextMove.coords[drive] -= tempMove.coords[drive];
+ // Extruder moves are relative, so we need to adjust the extrusion amounts in the original move
+ for (size_t drive = AXES; drive < DRIVES; ++drive)
+ {
+ nextMove.coords[drive] -= tempMove.coords[drive];
+ }
}
- }
- bool doMotorMapping = (moveType == 0) || (moveType == 1 && !IsDeltaMode());
+ bool doMotorMapping = (moveType == 0) || (moveType == 1 && !IsDeltaMode());
+ if (doMotorMapping)
+ {
+ Transform(tempMove);
+ }
+ if (ddaRingAddPointer->Init(tempMove.coords, nextMove.feedRate, nextMove.endStopsToCheck, doMotorMapping, nextMove.filePos))
+ {
+ ddaRingAddPointer = ddaRingAddPointer->GetNext();
+ idleCount = 0;
+ }
+ } while (isSegmented);
+#else // Use old code
+ bool doMotorMapping = (nextMove.moveType == 0) || (nextMove.moveType == 1 && !IsDeltaMode());
if (doMotorMapping)
{
- Transform(tempMove);
+ Transform(nextMove.coords);
}
- if (ddaRingAddPointer->Init(tempMove.coords, nextMove.feedRate, nextMove.endStopsToCheck, doMotorMapping, nextMove.filePos))
+ if (ddaRingAddPointer->Init(nextMove, doMotorMapping))
{
ddaRingAddPointer = ddaRingAddPointer->GetNext();
idleCount = 0;
}
- } while (isSegmented);
-#else // Use old code
- bool doMotorMapping = (nextMove.moveType == 0) || (nextMove.moveType == 1 && !IsDeltaMode());
- if (doMotorMapping)
- {
- Transform(nextMove.coords);
- }
- if (ddaRingAddPointer->Init(nextMove, doMotorMapping))
- {
- ddaRingAddPointer = ddaRingAddPointer->GetNext();
- idleCount = 0;
- }
#endif
+ }
}
}
}
@@ -216,27 +223,26 @@ void Move::Spin()
}
if (dda->GetState() == DDA::frozen)
{
- if (simulating)
+ if (simulationMode != 0)
{
currentDda = ddaRingGetPointer; // pretend we are executing this move
}
else
{
- cpu_irq_disable(); // must call StartNextMove and Interrupt with interrupts disabled
+ Platform::DisableStepInterrupt(); // should be disabled already, but make sure
if (StartNextMove(Platform::GetInterruptClocks())) // start the next move
{
Interrupt();
}
- cpu_irq_enable();
}
iState = IdleState::busy;
}
- else if (!simulating && iState == IdleState::busy && !reprap.GetGCodes()->IsPaused() && idleTimeout > 0.0)
+ else if (!simulationMode != 0 && iState == IdleState::busy && !reprap.GetGCodes()->IsPaused() && idleTimeout > 0.0)
{
lastMoveTime = reprap.GetPlatform()->Time(); // record when we first noticed that the machine was idle
iState = IdleState::timing;
}
- else if (!simulating && iState == IdleState::timing && reprap.GetPlatform()->Time() - lastMoveTime >= idleTimeout)
+ else if (!simulationMode != 0 && iState == IdleState::timing && reprap.GetPlatform()->Time() - lastMoveTime >= idleTimeout)
{
reprap.GetPlatform()->SetDrivesIdle(); // put all drives in idle hold
iState = IdleState::idle;
@@ -259,7 +265,7 @@ void Move::Spin()
}
// If the number of prepared moves will execute in less than the minimum time, prepare another move
- while (st == DDA::provisional && preparedTime < (int32_t)(DDA::stepClockRate/8)) // prepare moves one eighth of a second ahead of when they will be needed
+ while (st == DDA::provisional && preparedTime < (int32_t)(DDA::stepClockRate/8)) // prepare moves one eighth of a second ahead of when they will be needed
{
cdda->Prepare();
preparedTime += cdda->GetTimeLeft();
@@ -267,7 +273,7 @@ void Move::Spin()
st = cdda->GetState();
}
- if (simulating)
+ if (simulationMode != 0)
{
// Simulate completion of the current move
//DEBUG
@@ -318,7 +324,7 @@ FilePosition Move::PausePrint(float positions[DRIVES+1])
if (ddaRingAddPointer->GetState() == DDA::frozen)
{
// Change the state so that the ISR won't start executing this move
- ddaRingAddPointer->Free();
+ (void)ddaRingAddPointer->Free();
}
break;
}
@@ -361,7 +367,7 @@ FilePosition Move::PausePrint(float positions[DRIVES+1])
{
fPos = dda->GetFilePosition();
}
- dda->Free();
+ (void)dda->Free();
dda = dda->GetNext();
}
while (dda != savedDdaRingAddPointer);
@@ -381,11 +387,12 @@ extern uint32_t sqSum1, sqSum2, sqCount, sqErrors, lastRes1, lastRes2;
extern uint64_t lastNum;
#endif
-void Move::Diagnostics()
+void Move::Diagnostics(MessageType mtype)
{
- reprap.GetPlatform()->Message(GENERIC_MESSAGE, "Move Diagnostics:\n");
- reprap.GetPlatform()->MessageF(GENERIC_MESSAGE, "MaxReps: %u, StepErrors: %u\n", maxReps, stepErrors);
+ reprap.GetPlatform()->Message(mtype, "Move Diagnostics:\n");
+ reprap.GetPlatform()->MessageF(mtype, "MaxReps: %u, StepErrors: %u. Underruns: %u\n", maxReps, stepErrors, numLookaheadUnderruns);
maxReps = 0;
+ numLookaheadUnderruns = 0;
#if 0
if (sqCount != 0)
@@ -1402,10 +1409,10 @@ size_t Move::NumberOfXYProbePoints() const
}
// Enter or leave simulation mode
-void Move::Simulate(bool sim)
+void Move::Simulate(uint8_t simMode)
{
- simulating = sim;
- if (sim)
+ simulationMode = simMode;
+ if (simMode)
{
simulationTime = 0.0;
}
diff --git a/src/Move.h b/src/Move.h
index e8b3ed62..dca7e333 100644
--- a/src/Move.h
+++ b/src/Move.h
@@ -66,7 +66,7 @@ public:
void SetIdentityTransform(); // Cancel the bed equation; does not reset axis angle compensation
void Transform(float move[]) const; // Take a position and apply the bed and the axis-angle compensations
void InverseTransform(float move[]) const; // Go from a transformed point back to user coordinates
- void Diagnostics(); // Report useful stuff
+ void Diagnostics(MessageType mtype); // Report useful stuff
const DeltaParameters& GetDeltaParams() const { return deltaParams; }
DeltaParameters& AccessDeltaParams() { return deltaParams; }
@@ -89,7 +89,7 @@ public:
float IdleTimeout() const { return idleTimeout; } // Returns the idle timeout in seconds
void SetIdleTimeout(float timeout) { idleTimeout = timeout; } // Set the idle timeout in seconds
- void Simulate(bool sim); // Enter or leave simulation mode
+ void Simulate(uint8_t simMode); // Enter or leave simulation mode
float GetSimulationTime() const { return simulationTime; } // Get the accumulated simulation time
void PrintCurrentDda() const; // For debugging
@@ -136,7 +136,8 @@ private:
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?
+ uint8_t simulationMode; // Are we simulating, or really printing?
+ unsigned int numLookaheadUnderruns; // How many times we have run out of moves
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
volatile float liveCoordinates[DRIVES]; // The endpoint that the machine moved to in the last completed move
diff --git a/src/OutputMemory.cpp b/src/OutputMemory.cpp
index 366c89a8..19947ea4 100644
--- a/src/OutputMemory.cpp
+++ b/src/OutputMemory.cpp
@@ -496,9 +496,9 @@ size_t OutputBuffer::EncodeReply(OutputBuffer *src, bool allowControlChars)
}
}
-/*static*/ void OutputBuffer::Diagnostics()
+/*static*/ void OutputBuffer::Diagnostics(MessageType mtype)
{
- reprap.GetPlatform()->MessageF(GENERIC_MESSAGE, "Used output buffers: %d of %d (%d max)\n",
+ reprap.GetPlatform()->MessageF(mtype, "Used output buffers: %d of %d (%d max)\n",
usedOutputBuffers, OUTPUT_BUFFER_COUNT, maxUsedOutputBuffers);
}
diff --git a/src/OutputMemory.h b/src/OutputMemory.h
index b86b79dc..59edc645 100644
--- a/src/OutputMemory.h
+++ b/src/OutputMemory.h
@@ -8,9 +8,10 @@
#ifndef OUTPUTMEMORY_H_
#define OUTPUTMEMORY_H_
-#include "Arduino.h"
+#include "Core.h"
#include "Configuration.h"
#include "StringRef.h"
+#include "MessageType.h"
const size_t OUTPUT_STACK_DEPTH = 4; // Number of OutputBuffer chains that can be pushed onto one stack instance
@@ -76,7 +77,7 @@ class OutputBuffer
// Release all OutputBuffer objects in a chain
static void ReleaseAll(OutputBuffer *buf);
- static void Diagnostics();
+ static void Diagnostics(MessageType mtype);
private:
diff --git a/src/Platform.cpp b/src/Platform.cpp
index 509b2fff..437b4ff8 100644
--- a/src/Platform.cpp
+++ b/src/Platform.cpp
@@ -23,11 +23,16 @@
#include "DueFlashStorage.h"
#include "sam/drivers/tc/tc.h"
+#include "sam/drivers/hsmci/hsmci.h"
#ifdef EXTERNAL_DRIVERS
# include "ExternalDrivers.h"
#endif
+#ifdef DUET_NG
+# include "FirmwareUpdater.h"
+#endif
+
extern char _end;
extern "C" char *sbrk(int i);
@@ -729,12 +734,31 @@ void Platform::SetAutoSave(bool enabled)
#endif
}
+// Check the prerequisites for updating the main firmware. Return True if satisfied, else print as message and return false.
+bool Platform::CheckFirmwareUpdatePrerequisites()
+{
+ if (!GetMassStorage()->FileExists(GetSysDir(), IAP_FIRMWARE_FILE))
+ {
+ MessageF(GENERIC_MESSAGE, "Error: Firmware binary \"%s\" not found\n", IAP_FIRMWARE_FILE);
+ return false;
+ }
+
+ if (!GetMassStorage()->FileExists(GetSysDir(), IAP_UPDATE_FILE))
+ {
+ MessageF(GENERIC_MESSAGE, "Error: In-application programming binary \"%s\" not found\n", IAP_UPDATE_FILE);
+ return false;
+ }
+
+ return true;
+}
+
+// Update the firmware. Prerequisites should be checked before calling this.
void Platform::UpdateFirmware()
{
FileStore *iapFile = GetFileStore(GetSysDir(), IAP_UPDATE_FILE, false);
if (iapFile == nullptr)
{
- MessageF(GENERIC_MESSAGE, "Error: Could not open IAP programmer binary \"%s\"\n", IAP_UPDATE_FILE);
+ MessageF(FIRMWARE_UPDATE_MESSAGE, "IAP not found\n");
return;
}
@@ -754,7 +778,7 @@ void Platform::UpdateFirmware()
#if (SAM4S || SAM4E)
// The EWP command is not supported for non-8KByte sectors in the SAM4 series.
- // So unlock and erase the complete 64Kb sector first.
+ // So we have to unlock and erase the complete 64Kb sector first.
// TODO save the NVRAM area and restore it later
flash_unlock(IAP_FLASH_START, IAP_FLASH_END, nullptr, nullptr);
@@ -779,13 +803,13 @@ void Platform::UpdateFirmware()
if (rc != FLASH_RC_OK)
{
- MessageF(GENERIC_MESSAGE, "Error: Flash write failed, code=%u, address=0x%08x\n", rc, flashAddr);
+ MessageF(FIRMWARE_UPDATE_MESSAGE, "Error: Flash write failed, code=%u, address=0x%08x\n", rc, flashAddr);
return;
}
// Verify written data
if (memcmp(reinterpret_cast<void *>(flashAddr), data, bytesRead) != 0)
{
- MessageF(GENERIC_MESSAGE, "Error: Verify during flash write failed, address=0x%08x\n", flashAddr);
+ MessageF(FIRMWARE_UPDATE_MESSAGE, "Error: Verify during flash write failed, address=0x%08x\n", flashAddr);
return;
}
}
@@ -836,13 +860,13 @@ void Platform::UpdateFirmware()
if (rc != FLASH_RC_OK)
{
- MessageF(GENERIC_MESSAGE, "Error: Flash %s failed, code=%u, address=0x%08x\n", op, rc, flashAddr);
+ MessageF(FIRMWARE_UPDATE_MESSAGE, "Error: Flash %s failed, code=%u, address=0x%08x\n", op, rc, flashAddr);
return;
}
// Verify written data
if (memcmp(reinterpret_cast<void *>(flashAddr), data, bytesRead) != 0)
{
- MessageF(GENERIC_MESSAGE, "Error: Verify during flash write failed, address=0x%08x\n", flashAddr);
+ MessageF(FIRMWARE_UPDATE_MESSAGE, "Error: Verify during flash write failed, address=0x%08x\n", flashAddr);
return;
}
}
@@ -860,6 +884,11 @@ void Platform::UpdateFirmware()
#endif
iapFile->Close();
+ Message(FIRMWARE_UPDATE_MESSAGE, "Updating main firmware\n");
+
+ // Allow time for the firmware update message to be sent
+ uint32_t now = millis();
+ while (FlushMessages() && millis() - now < 2000) { }
// Step 2 - Let the firmware do whatever is necessary before we exit this program
reprap.Exit();
@@ -925,16 +954,13 @@ void Platform::Exit()
}
}
- // Stop processing data
- Message(GENERIC_MESSAGE, "Platform class exited.\n");
+ // Stop processing data. Don't try to send a message because it will probably never get there.
active = false;
}
Compatibility Platform::Emulating() const
{
- if (nvData.compatibility == reprapFirmware)
- return me;
- return nvData.compatibility;
+ return (nvData.compatibility == reprapFirmware) ? me : nvData.compatibility;
}
void Platform::SetEmulating(Compatibility c)
@@ -990,21 +1016,9 @@ void Platform::SetNetMask(byte nm[])
UpdateNetworkAddress(nvData.netMask, nm);
}
-void Platform::Spin()
+// Flush messages to USB and aux, returning true if there is more to send
+bool Platform::FlushMessages()
{
- if (!active)
- return;
-
- // Check if any files are supposed to be closed
- for(size_t i = 0; i < MAX_FILES; i++)
- {
- if (files[i]->closeRequested)
- {
- // We cannot do this in ISRs, so do it here
- files[i]->Close();
- }
- }
-
// Write non-blocking data to the AUX line
OutputBuffer *auxOutputBuffer = auxOutput->GetFirstItem();
if (auxOutputBuffer != nullptr)
@@ -1070,6 +1084,29 @@ void Platform::Spin()
}
}
+ return auxOutput->GetFirstItem() != nullptr
+ || aux2Output->GetFirstItem() != nullptr
+ || usbOutput->GetFirstItem() != nullptr;
+}
+
+void Platform::Spin()
+{
+ if (!active)
+ return;
+
+ // Check if any files are supposed to be closed
+ for(size_t i = 0; i < MAX_FILES; i++)
+ {
+ if (files[i]->closeRequested)
+ {
+ // We cannot do this in ISRs, so do it here
+ files[i]->Close();
+ }
+ }
+
+ // Try to flush messages to serial ports
+ (void)FlushMessages();
+
// Thermostatically-controlled fans
for (size_t fan = 0; fan < NUM_FANS; ++fan)
{
@@ -1133,16 +1170,6 @@ void Platform::SoftwareReset(uint16_t reason)
// Interrupts
-void STEP_TC_HANDLER()
-{
- STEP_TC->TC_CHANNEL[STEP_TC_CHAN].TC_IDR = TC_IER_CPAS; // disable the interrupt
-#ifdef MOVE_DEBUG
- ++numInterruptsExecuted;
- lastInterruptTime = Platform::GetInterruptClocks();
-#endif
- reprap.GetMove()->Interrupt();
-}
-
#ifndef DUET_NG
void NETWORK_TC_HANDLER()
{
@@ -1231,27 +1258,27 @@ void Platform::DisableInterrupts()
// This diagnostics function is the first to be called, so it calls Message to start with.
// All other messages generated by this and other diagnostics functions must call AppendMessage.
-void Platform::Diagnostics()
+void Platform::Diagnostics(MessageType mtype)
{
- Message(GENERIC_MESSAGE, "Platform Diagnostics:\n");
+ Message(mtype, "Platform Diagnostics:\n");
// Print memory stats and error codes to USB and copy them to the current webserver reply
const char *ramstart = (char *) 0x20070000;
const struct mallinfo mi = mallinfo();
- Message(GENERIC_MESSAGE, "Memory usage:\n");
- MessageF(GENERIC_MESSAGE, "Program static ram used: %d\n", &_end - ramstart);
- MessageF(GENERIC_MESSAGE, "Dynamic ram used: %d\n", mi.uordblks);
- MessageF(GENERIC_MESSAGE, "Recycled dynamic ram: %d\n", mi.fordblks);
+ Message(mtype, "Memory usage:\n");
+ MessageF(mtype, "Program static ram used: %d\n", &_end - ramstart);
+ MessageF(mtype, "Dynamic ram used: %d\n", mi.uordblks);
+ MessageF(mtype, "Recycled dynamic ram: %d\n", mi.fordblks);
size_t currentStack, maxStack, neverUsed;
GetStackUsage(&currentStack, &maxStack, &neverUsed);
- MessageF(GENERIC_MESSAGE, "Current stack ram used: %d\n", currentStack);
- MessageF(GENERIC_MESSAGE, "Maximum stack ram used: %d\n", maxStack);
- MessageF(GENERIC_MESSAGE, "Never used ram: %d\n", neverUsed);
+ MessageF(mtype, "Current stack ram used: %d\n", currentStack);
+ MessageF(mtype, "Maximum stack ram used: %d\n", maxStack);
+ MessageF(mtype, "Never used ram: %d\n", neverUsed);
// Show the up time and reason for the last reset
const uint32_t now = (uint32_t)Time(); // get up time in seconds
const char* resetReasons[8] = { "power up", "backup", "watchdog", "software", "external", "?", "?", "?" };
- MessageF(GENERIC_MESSAGE, "Last reset %02d:%02d:%02d ago, cause: %s\n",
+ MessageF(mtype, "Last reset %02d:%02d:%02d ago, cause: %s\n",
(unsigned int)(now/3600), (unsigned int)((now % 3600)/60), (unsigned int)(now % 60),
resetReasons[(REG_RSTC_SR & RSTC_SR_RSTTYP_Msk) >> RSTC_SR_RSTTYP_Pos]);
@@ -1262,21 +1289,21 @@ void Platform::Diagnostics()
DueFlashStorage::read(SoftwareResetData::nvAddress, &temp, sizeof(SoftwareResetData));
if (temp.magic == SoftwareResetData::magicValue && temp.version == SoftwareResetData::versionValue)
{
- MessageF(GENERIC_MESSAGE, "Last software reset code & available RAM: 0x%04x, %u\n", temp.resetReason, temp.neverUsedRam);
- MessageF(GENERIC_MESSAGE, "Spinning module during software reset: %s\n", moduleName[temp.resetReason & 0x0F]);
+ MessageF(mtype, "Last software reset code & available RAM: 0x%04x, %u\n", temp.resetReason, temp.neverUsedRam);
+ MessageF(mtype, "Spinning module during software reset: %s\n", moduleName[temp.resetReason & 0x0F]);
}
}
// Show the current error codes
- MessageF(GENERIC_MESSAGE, "Error status: %u\n", errorCodeBits);
+ MessageF(mtype, "Error status: %u\n", errorCodeBits);
// Show the current probe position heights
- Message(GENERIC_MESSAGE, "Bed probe heights:");
+ Message(mtype, "Bed probe heights:");
for (size_t i = 0; i < MAX_PROBE_POINTS; ++i)
{
- MessageF(GENERIC_MESSAGE, " %.3f", reprap.GetMove()->ZBedProbePoint(i));
+ MessageF(mtype, " %.3f", reprap.GetMove()->ZBedProbePoint(i));
}
- Message(GENERIC_MESSAGE, "\n");
+ Message(mtype, "\n");
// Show the number of free entries in the file table
unsigned int numFreeFiles = 0;
@@ -1287,13 +1314,16 @@ void Platform::Diagnostics()
++numFreeFiles;
}
}
- MessageF(GENERIC_MESSAGE, "Free file entries: %u\n", numFreeFiles);
+ MessageF(mtype, "Free file entries: %u\n", numFreeFiles);
// Show the longest write time
- MessageF(GENERIC_MESSAGE, "Longest block write time: %.1fms\n", FileStore::GetAndClearLongestWriteTime());
+ MessageF(mtype, "Longest block write time: %.1fms\n", FileStore::GetAndClearLongestWriteTime());
+
+ // Show the HSMCI speed
+ MessageF(mtype, "SD card speed: %.1fMHz\n", (float)hsmci_get_speed()/1000000.0);
// Debug
-//MessageF(GENERIC_MESSAGE, "Shortest/longest times read %.1f/%.1f write %.1f/%.1f ms, %u/%u\n",
+//MessageF(mtype, "Shortest/longest times read %.1f/%.1f write %.1f/%.1f ms, %u/%u\n",
// (float)shortestReadWaitTime/1000, (float)longestReadWaitTime/1000, (float)shortestWriteWaitTime/1000, (float)longestWriteWaitTime/1000,
// maxRead, maxWrite);
//longestWriteWaitTime = longestReadWaitTime = 0; shortestReadWaitTime = shortestWriteWaitTime = 1000000;
@@ -1301,7 +1331,7 @@ void Platform::Diagnostics()
reprap.Timing();
#ifdef MOVE_DEBUG
- MessageF(GENERIC_MESSAGE, "Interrupts scheduled %u, done %u, last %u, next %u sched at %u, now %u\n",
+ MessageF(mtype, "Interrupts scheduled %u, done %u, last %u, next %u sched at %u, now %u\n",
numInterruptsScheduled, numInterruptsExecuted, lastInterruptTime, nextInterruptTime, nextInterruptScheduledAt, GetInterruptClocks());
#endif
}
@@ -1576,6 +1606,21 @@ EndStopHit Platform::Stopped(size_t drive) const
return EndStopHit::noStop;
}
+// Get the statues of all the endstop inputs, regardless of what they are used for. Used for triggers.
+uint32_t Platform::GetAllEndstopStates() const
+{
+ uint32_t rslt = 0;
+ for (unsigned int drive = 0; drive < DRIVES; ++drive)
+ {
+ const Pin pin = endStopPins[drive];
+ if (pin >= 0 && digitalRead(pin))
+ {
+ rslt |= (1 << drive);
+ }
+ }
+ return rslt;
+}
+
// Return the Z probe result. We assume that if the Z probe is used as an endstop, it is used as the low stop.
EndStopHit Platform::GetZProbeResult() const
{
@@ -2069,12 +2114,6 @@ void Platform::Message(MessageType type, const char *message)
{
switch (type)
{
- case FLASH_LED:
- // Message that is to flash an LED; the next two bytes define
- // the frequency and M/S ratio.
- // (not implemented yet)
- break;
-
case AUX_MESSAGE:
// Message that is to be sent to the first auxiliary device
if (!auxOutput->IsEmpty())
@@ -2107,11 +2146,6 @@ void Platform::Message(MessageType type, const char *message)
#endif
break;
- case DISPLAY_MESSAGE:
- // Message that is to appear on a local display; \f and \n should be supported.
- reprap.SetMessage(message);
- break;
-
case DEBUG_MESSAGE:
// Debug messages in blocking mode - potentially DANGEROUS, use with care!
SERIAL_MAIN_DEVICE.write(message);
@@ -2163,21 +2197,32 @@ void Platform::Message(MessageType type, const char *message)
}
break;
+ case FIRMWARE_UPDATE_MESSAGE:
+ Message(HOST_MESSAGE, message);
+ // Send an alert message to the aux port
+ {
+ OutputBuffer *buf;
+ if (OutputBuffer::Allocate(buf, false))
+ {
+ buf->cat("{\"alert\":");
+ buf->EncodeString(message, strlen(message), true, true);
+ buf->cat("}\n");
+ Message(AUX_MESSAGE, buf);
+ }
+ }
+ break;
+
case GENERIC_MESSAGE:
// Message that is to be sent to the web & host. Make this the default one, too.
default:
Message(HTTP_MESSAGE, message);
Message(TELNET_MESSAGE, message);
Message(HOST_MESSAGE, message);
+ Message(AUX_MESSAGE, message);
break;
}
}
-void Platform::Message(const MessageType type, const StringRef &message)
-{
- Message(type, message.Pointer());
-}
-
void Platform::Message(const MessageType type, OutputBuffer *buffer)
{
switch (type)
@@ -2234,10 +2279,16 @@ void Platform::Message(const MessageType type, OutputBuffer *buffer)
case GENERIC_MESSAGE:
// Message that is to be sent to the web & host.
- buffer->IncreaseReferences(2); // This one is handled by two additional destinations
+ buffer->IncreaseReferences(3); // This one is handled by three additional destinations
Message(HTTP_MESSAGE, buffer);
Message(TELNET_MESSAGE, buffer);
Message(HOST_MESSAGE, buffer);
+ Message(AUX_MESSAGE, buffer);
+ break;
+
+ case FIRMWARE_UPDATE_MESSAGE:
+ // We don't generate any of these with an OutputBuffer argument, but if we get one, just send it to USB
+ Message(HOST_MESSAGE, buffer);
break;
default:
@@ -2517,6 +2568,17 @@ char Platform::ReadFromSource(const SerialSource source)
//#pragma GCC push_options
#pragma GCC optimize ("O3")
+// Step pulse timer interrupt
+void STEP_TC_HANDLER()
+{
+ STEP_TC->TC_CHANNEL[STEP_TC_CHAN].TC_IDR = TC_IER_CPAS; // disable the interrupt
+#ifdef MOVE_DEBUG
+ ++numInterruptsExecuted;
+ lastInterruptTime = Platform::GetInterruptClocks();
+#endif
+ reprap.GetMove()->Interrupt();
+}
+
// Schedule an interrupt at the specified clock count, or return true if that time is imminent or has passed already.
// Must be called with interrupts disabled,
/*static*/ bool Platform::ScheduleInterrupt(uint32_t tim)
@@ -2538,6 +2600,12 @@ char Platform::ReadFromSource(const SerialSource source)
return false;
}
+// Make sure we get no step interrupts
+/*static*/ void Platform::DisableStepInterrupt()
+{
+ STEP_TC->TC_CHANNEL[STEP_TC_CHAN].TC_IDR = TC_IER_CPAS;
+}
+
// Process a 1ms tick interrupt
// This function must be kept fast so as not to disturb the stepper timing, so don't do any floating point maths in here.
// This is what we need to do:
diff --git a/src/Platform.h b/src/Platform.h
index 956917aa..67a40182 100644
--- a/src/Platform.h
+++ b/src/Platform.h
@@ -46,12 +46,13 @@ Licence: GPL
// Platform-specific includes
-#include "Arduino.h"
+#include "Core.h"
#include "OutputMemory.h"
#include "ff.h"
#include "MCP4461.h"
#include "MassStorage.h"
#include "FileStore.h"
+#include "MessageType.h"
// Definitions needed by Pins.h
@@ -396,20 +397,6 @@ enum class SerialSource
AUX2
};
-// Supported message destinations
-enum MessageType
-{
- AUX_MESSAGE, // Type byte of a message that is to be sent to the first auxiliary device
- AUX2_MESSAGE, // Type byte of a message that is to be sent to the second auxiliary device
- FLASH_LED, // Type byte of a message that is to flash an LED; the next two bytes define the frequency and M/S ratio
- DISPLAY_MESSAGE, // Type byte of a message that is to appear on a local display; the L is not displayed; \f and \n should be supported
- HOST_MESSAGE, // Type byte of a message that is to be sent in non-blocking mode to the host via USB
- DEBUG_MESSAGE, // Type byte of a debug message to send in blocking mode to USB
- HTTP_MESSAGE, // Type byte of a message that is to be sent to the web (HTTP)
- TELNET_MESSAGE, // Type byte of a message that is to be sent to a Telnet client
- GENERIC_MESSAGE, // Type byte of a message that is to be sent to the web & host
-};
-
// The main class that defines the RepRap machine for the benefit of the other classes
class Platform
@@ -434,7 +421,7 @@ public:
Compatibility Emulating() const;
void SetEmulating(Compatibility c);
- void Diagnostics();
+ void Diagnostics(MessageType mtype);
void DiagnosticTest(int d);
void ClassReport(float &lastTime); // Called on Spin() return to check everything's live.
void RecordError(ErrorCode ec) { errorCodeBits |= (uint32_t)ec; }
@@ -449,6 +436,7 @@ public:
float Time(); // Returns elapsed seconds since some arbitrary time
static uint32_t GetInterruptClocks(); // Get the interrupt clock count
static bool ScheduleInterrupt(uint32_t tim); // Schedule an interrupt at the specified clock count, or return true if it has passed already
+ static void DisableStepInterrupt(); // Make sure we get no step interrupts
void Tick();
// Communications and data storage
@@ -473,21 +461,21 @@ public:
MassStorage* GetMassStorage() const;
FileStore* GetFileStore(const char* directory, const char* fileName, bool write);
- const char* GetWebDir() const; // Where the htm etc files are
- const char* GetGCodeDir() const; // Where the gcodes are
- const char* GetSysDir() const; // Where the system files are
- const char* GetMacroDir() const; // Where the user-defined macros are
- const char* GetConfigFile() const; // Where the configuration is stored (in the system dir).
- const char* GetDefaultFile() const; // Where the default configuration is stored (in the system dir).
- void InvalidateFiles(); // Called to invalidate files when the SD card is removed
+ const char* GetWebDir() const; // Where the htm etc files are
+ const char* GetGCodeDir() const; // Where the gcodes are
+ const char* GetSysDir() const; // Where the system files are
+ const char* GetMacroDir() const; // Where the user-defined macros are
+ const char* GetConfigFile() const; // Where the configuration is stored (in the system dir).
+ const char* GetDefaultFile() const; // Where the default configuration is stored (in the system dir).
+ void InvalidateFiles(); // Called to invalidate files when the SD card is removed
// Message output (see MessageType for further details)
void Message(const MessageType type, const char *message);
- void Message(const MessageType type, const StringRef& message);
void Message(const MessageType type, OutputBuffer *buffer);
void MessageF(const MessageType type, const char *fmt, ...);
void MessageF(const MessageType type, const char *fmt, va_list vargs);
+ bool FlushMessages(); // Flush messages to USB and aux, returning true if there is more to send
// Movement
@@ -534,6 +522,7 @@ public:
void SetElasticComp(size_t extruder, float factor);
void SetEndStopConfiguration(size_t axis, EndStopType endstopType, bool logicLevel);
void GetEndStopConfiguration(size_t axis, EndStopType& endstopType, bool& logicLevel) const;
+ uint32_t GetAllEndstopStates() const;
// Z probe
@@ -598,6 +587,7 @@ public:
void SetAutoSave(bool enabled);
void UpdateFirmware();
+ bool CheckFirmwareUpdatePrerequisites();
// AUX device
void Beep(int freq, int ms);
diff --git a/src/RepRapFirmware.h b/src/RepRapFirmware.h
index 33510529..414c9d3d 100644
--- a/src/RepRapFirmware.h
+++ b/src/RepRapFirmware.h
@@ -26,7 +26,7 @@ Licence: GPL
#include <cfloat>
#include <cstdarg>
-#include "Arduino.h"
+#include "Core.h"
#include "Configuration.h"
#include "StringRef.h"
@@ -75,10 +75,6 @@ bool StringStartsWith(const char* string, const char* starting);
bool StringEquals(const char* s1, const char* s2);
int StringContains(const char* string, const char* match);
-// Macro to give us the number of elements in an array
-#define ARRAY_SIZE(_x) (sizeof(_x)/sizeof(_x[0]))
-// Macro to give us the highest valid index into an array i.e. one less than the size
-#define ARRAY_UPB(_x) (ARRAY_SIZE(_x) - 1)
// Macro to assign an array from an initializer list
#define ARRAY_INIT(_dest, _init) static_assert(sizeof(_dest) == sizeof(_init), "Incompatible array types"); memcpy(_dest, _init, sizeof(_init));
@@ -96,70 +92,6 @@ extern StringRef scratchString;
#include "PrintMonitor.h"
#include "Reprap.h"
-// std::min and std::max don't seem to work with this variant of gcc, so define our own ones here
-// We use these only with primitive types, so pass them directly instead of by const reference
-#undef min
-#undef max
-
-template<class X> inline X min(X _a, X _b)
-{
- return (_a < _b) ? _a : _b;
-}
-
-template<class X> inline X max(X _a, X _b)
-{
- return (_a > _b) ? _a : _b;
-}
-
-// Specialisations for float and double to handle NANs properly
-template<> inline float min(float _a, float _b)
-{
- return (isnan(_a) || _a < _b) ? _a : _b;
-}
-
-template<> inline float max(float _a, float _b)
-{
- return (isnan(_a) || _a > _b) ? _a : _b;
-}
-
-template<> inline double min(double _a, double _b)
-{
- return (isnan(_a) || _a < _b) ? _a : _b;
-}
-
-template<> inline double max(double _a, double _b)
-{
- return (isnan(_a) || _a > _b) ? _a : _b;
-}
-
-inline float fsquare(float arg)
-{
- return arg * arg;
-}
-
-inline uint64_t isquare64(int32_t arg)
-{
- return (uint64_t)((int64_t)arg * arg);
-}
-
-inline uint64_t isquare64(uint32_t arg)
-{
- return (uint64_t)arg * arg;
-}
-
-inline void swap(float& a, float& b)
-{
- float temp = a;
- a = b;
- b = temp;
-}
-
-#undef constrain
-template<class T> inline float constrain(T val, T vmin, T vmax)
-{
- return max<T>(vmin, min<T>(val, vmax));
-}
-
extern uint32_t isqrt64(uint64_t num); // This is defined in its own file, Isqrt.cpp or Isqrt.asm
#endif
diff --git a/src/Reprap.cpp b/src/Reprap.cpp
index acae8f9c..afbf8202 100644
--- a/src/Reprap.cpp
+++ b/src/Reprap.cpp
@@ -185,16 +185,16 @@ void RepRap::Timing()
slowLoop = 0.0;
}
-void RepRap::Diagnostics()
+void RepRap::Diagnostics(MessageType mtype)
{
- platform->Message(GENERIC_MESSAGE, "Diagnostics\n");
- OutputBuffer::Diagnostics();
- platform->Diagnostics(); // this includes a call to our Timing() function
- move->Diagnostics();
- heat->Diagnostics();
- gCodes->Diagnostics();
- network->Diagnostics();
- webserver->Diagnostics();
+ platform->Message(mtype, "Diagnostics\n");
+ OutputBuffer::Diagnostics(mtype);
+ platform->Diagnostics(mtype); // this includes a call to our Timing() function
+ move->Diagnostics(mtype);
+ heat->Diagnostics(mtype);
+ gCodes->Diagnostics(mtype);
+ network->Diagnostics(mtype);
+ webserver->Diagnostics(mtype);
}
// Turn off the heaters, disable the motors, and
diff --git a/src/Reprap.h b/src/Reprap.h
index 587d5161..cdd364a2 100644
--- a/src/Reprap.h
+++ b/src/Reprap.h
@@ -37,7 +37,7 @@ public:
void Init();
void Spin();
void Exit();
- void Diagnostics();
+ void Diagnostics(MessageType mtype);
void Timing();
bool Debug(Module module) const;
diff --git a/src/StringRef.cpp b/src/StringRef.cpp
index 28954925..80b317c7 100644
--- a/src/StringRef.cpp
+++ b/src/StringRef.cpp
@@ -66,6 +66,18 @@ size_t StringRef::cat(const char* src)
return length;
}
+// Append a character
+size_t StringRef::cat(char c)
+{
+ size_t length = strlen();
+ if (length + 1 < len)
+ {
+ p[length++] = c;
+ p[length] = 0;
+ }
+ return length;
+}
+
// End
diff --git a/src/StringRef.h b/src/StringRef.h
index 7254413d..dd9ece2a 100644
--- a/src/StringRef.h
+++ b/src/StringRef.h
@@ -37,6 +37,7 @@ public:
int catf(const char *fmt, ...);
size_t copy(const char* src);
size_t cat(const char *src);
+ size_t cat(char c);
};
#endif /* STRINGREF_H_ */