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:
-rw-r--r--.cproject160
-rw-r--r--.settings/org.eclipse.cdt.core.prefs11
-rw-r--r--BuildInstructions.txt2
-rw-r--r--Release/RepRapFirmware-1.09z-rc1-dc42.binbin0 -> 273356 bytes
-rw-r--r--SD-image/sys-CoreXY/iap.binbin30280 -> 48416 bytes
-rw-r--r--SD-image/sys-Fisher/iap.binbin30280 -> 48416 bytes
-rw-r--r--SD-image/sys-Huxley/iap.binbin30280 -> 48416 bytes
-rw-r--r--SD-image/sys-MiniKossel/NoEndstops.g30
-rw-r--r--SD-image/sys-MiniKossel/iap.binbin30280 -> 48416 bytes
-rw-r--r--SD-image/sys-Ormerod1/iap.binbin30280 -> 48416 bytes
-rw-r--r--SD-image/sys-Ormerod2/iap.binbin30280 -> 48416 bytes
-rw-r--r--src/Configuration.h6
-rw-r--r--src/DDA.cpp3
-rw-r--r--src/DDA.h2
-rw-r--r--src/FileStore.cpp42
-rw-r--r--src/FileStore.h11
-rw-r--r--src/GCodeBuffer.cpp6
-rw-r--r--src/GCodes.cpp310
-rw-r--r--src/GCodes.h37
-rw-r--r--src/MassStorage.cpp73
-rw-r--r--src/Move.cpp47
-rw-r--r--src/Move.h6
-rw-r--r--src/Network.cpp855
-rw-r--r--src/Network.h117
-rw-r--r--src/OutputMemory.cpp6
-rw-r--r--src/Platform.cpp90
-rw-r--r--src/Platform.h63
-rw-r--r--src/PrintMonitor.cpp29
-rw-r--r--src/PrintMonitor.h4
-rw-r--r--src/RepRapFirmware.h2
-rw-r--r--src/Tool.cpp5
-rw-r--r--src/Tool.h16
-rw-r--r--src/Webserver.cpp717
-rw-r--r--src/Webserver.h80
34 files changed, 1622 insertions, 1108 deletions
diff --git a/.cproject b/.cproject
index 0bafdee2..782f54ef 100644
--- a/.cproject
+++ b/.cproject
@@ -2,7 +2,10 @@
<?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="Release">
+ <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"/>
@@ -14,7 +17,7 @@
</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="Release" parent="cdt.managedbuild.config.gnu.cross.exe.release" postannouncebuildStep="Generating binary file" postbuildStep="arm-none-eabi-objcopy -O binary ${workspace_loc:/${ProjName}/Release}/${ProjName}.elf ${workspace_loc:/${ProjName}/Release}/${ProjName}.bin">
+ <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"/>
@@ -30,13 +33,13 @@
<option id="gnu.c.compiler.option.misc.verbose.1564280355" name="Verbose (-v)" superClass="gnu.c.compiler.option.misc.verbose" value="false" valueType="boolean"/>
<option id="gnu.c.compiler.option.misc.other.96683616" name="Other flags" superClass="gnu.c.compiler.option.misc.other" 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" valueType="includePath">
- <listOptionValue builtIn="false" value="&quot;${workspace_loc:/CoreDuet/cores/arduino}&quot;"/>
- <listOptionValue builtIn="false" value="&quot;${workspace_loc:/CoreDuet/system/libsam}&quot;"/>
- <listOptionValue builtIn="false" value="&quot;${workspace_loc:/CoreDuet/system/CMSIS/Device/ATMEL}&quot;"/>
- <listOptionValue builtIn="false" value="&quot;${workspace_loc:/CoreDuet/system/CMSIS/CMSIS/Include}&quot;"/>
- <listOptionValue builtIn="false" value="&quot;${workspace_loc:/CoreDuet/variants/duet}&quot;"/>
- <listOptionValue builtIn="false" value="&quot;${workspace_loc:/CoreDuet/system/libsam/include}&quot;"/>
- <listOptionValue builtIn="false" value="&quot;${workspace_loc:/CoreDuet/system/CMSIS/Device/ATMEL/sam3xa/include}&quot;"/>
+ <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:/${ProjName}/Libraries/SD_HSMCI/utility}&quot;"/>
<listOptionValue builtIn="false" value="&quot;${workspace_loc:/${ProjName}/Libraries/SPI}&quot;"/>
<listOptionValue builtIn="false" value="&quot;${workspace_loc:/${ProjName}/Libraries/Lwip}&quot;"/>
@@ -55,15 +58,15 @@
</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:/CoreDuet/Release/cores/arduino/syscalls_sam3.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">
+ <tool command="gcc" commandLinePattern="${COMMAND} ${FLAGS} ${OUTPUT_FLAG} ${OUTPUT_PREFIX}${OUTPUT} ${LINK_FLAGS_1} ${workspace_loc:/${CoreName}/Release/cores/arduino/syscalls_sam3.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:/CoreDuet/Release/}&quot;"/>
+ <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="CoreDuet"/>
+ <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 -mcpu=cortex-m3 -T${workspace_loc:/CoreDuet/variants/duet/linker_scripts/gcc/flash.ld} -Wl,-Map,${workspace_loc:/${ProjName}/Release}/${ProjName}.map" valueType="string"/>
+ <option id="gnu.cpp.link.option.flags.1874922881" name="Linker flags" superClass="gnu.cpp.link.option.flags" value="-Os -Wl,--gc-sections -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)"/>
@@ -75,12 +78,12 @@
<option id="gnu.cpp.compiler.option.other.verbose.526148117" name="Verbose (-v)" superClass="gnu.cpp.compiler.option.other.verbose" value="false" valueType="boolean"/>
<option id="gnu.cpp.compiler.option.other.other.1337488452" name="Other flags" superClass="gnu.cpp.compiler.option.other.other" 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" valueType="includePath">
- <listOptionValue builtIn="false" value="&quot;${workspace_loc:/CoreDuet/cores/arduino}&quot;"/>
- <listOptionValue builtIn="false" value="&quot;${workspace_loc:/CoreDuet/system/libsam}&quot;"/>
- <listOptionValue builtIn="false" value="&quot;${workspace_loc:/CoreDuet/system/CMSIS/Device/ATMEL}&quot;"/>
- <listOptionValue builtIn="false" value="&quot;${workspace_loc:/CoreDuet/system/CMSIS/CMSIS/Include}&quot;"/>
- <listOptionValue builtIn="false" value="&quot;${workspace_loc:/CoreDuet/variants/duet}&quot;"/>
- <listOptionValue builtIn="false" value="&quot;${workspace_loc:/CoreDuet/system/libsam/include}&quot;"/>
+ <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:/${ProjName}/Libraries/Lwip}&quot;"/>
<listOptionValue builtIn="false" value="&quot;${workspace_loc:/${ProjName}/Libraries/EMAC}&quot;"/>
<listOptionValue builtIn="false" value="&quot;${workspace_loc:/${ProjName}/Libraries/SD_HSMCI}&quot;"/>
@@ -110,6 +113,119 @@
</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="ReleaseWithCoreNG">
+ <macros>
+ <stringMacro name="CoreName" type="VALUE_TEXT" value="CoreNG"/>
+ </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.976458850" name="ReleaseWithCoreNG" 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.976458850." name="/" resourcePath="">
+ <toolChain id="cdt.managedbuild.toolchain.gnu.cross.exe.release.947353540" name="Cross GCC" superClass="cdt.managedbuild.toolchain.gnu.cross.exe.release">
+ <option id="cdt.managedbuild.option.gnu.cross.path.1742191832" 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.1660769040" 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.223860525" isAbstract="false" osList="all" superClass="cdt.managedbuild.targetPlatform.gnu.cross"/>
+ <builder buildPath="${workspace_loc:/RepRapFirmware}/Release" id="cdt.managedbuild.builder.gnu.cross.13059261" keepEnvironmentInBuildfile="false" managedBuildOn="true" name="Gnu Make Builder" superClass="cdt.managedbuild.builder.gnu.cross"/>
+ <tool id="cdt.managedbuild.tool.gnu.cross.assembler.163742171" name="Cross GCC Assembler" superClass="cdt.managedbuild.tool.gnu.cross.assembler">
+ <inputType id="cdt.managedbuild.tool.gnu.assembler.input.230262206" 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.278237460" 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.710346403" name="Optimization Level" superClass="gnu.c.compiler.option.optimization.level" valueType="enumerated"/>
+ <option id="gnu.c.compiler.option.debugging.level.836865552" name="Debug Level" superClass="gnu.c.compiler.option.debugging.level" value="gnu.c.debugging.level.none" valueType="enumerated"/>
+ <option id="gnu.c.compiler.option.misc.verbose.431575256" name="Verbose (-v)" superClass="gnu.c.compiler.option.misc.verbose" value="false" valueType="boolean"/>
+ <option id="gnu.c.compiler.option.misc.other.660952665" name="Other flags" superClass="gnu.c.compiler.option.misc.other" 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.2080437508" name="Include paths (-I)" superClass="gnu.c.compiler.option.include.paths" valueType="includePath">
+ <listOptionValue builtIn="false" value="&quot;${workspace_loc:/${CoreName}/cores/arduino}&quot;"/>
+ <listOptionValue builtIn="false" value="&quot;${workspace_loc:/${CoreName}/asf}&quot;"/>
+ <listOptionValue builtIn="false" value="&quot;${workspace_loc:/${CoreName}/asf/common/utils}&quot;"/>
+ <listOptionValue builtIn="false" value="&quot;${workspace_loc:/${CoreName}/asf/sam/utils}&quot;"/>
+ <listOptionValue builtIn="false" value="&quot;${workspace_loc:/${CoreName}/asf/sam/utils/cmsis/sam3x/include}&quot;"/>
+ <listOptionValue builtIn="false" value="&quot;${workspace_loc:/${CoreName}/asf/sam/utils/cmsis/sam3x/source/templates}&quot;"/>
+ <listOptionValue builtIn="false" value="&quot;${workspace_loc:/${CoreName}/asf/sam/utils/header_files}&quot;"/>
+ <listOptionValue builtIn="false" value="&quot;${workspace_loc:/${CoreName}/asf/thirdparty/CMSIS/Include}&quot;"/>
+ <listOptionValue builtIn="false" value="&quot;${workspace_loc:/${CoreName}/variants/duet}&quot;"/>
+ <listOptionValue builtIn="false" value="&quot;${workspace_loc:/${ProjName}/Libraries/SD_HSMCI/utility}&quot;"/>
+ <listOptionValue builtIn="false" value="&quot;${workspace_loc:/${ProjName}/Libraries/SPI}&quot;"/>
+ <listOptionValue builtIn="false" value="&quot;${workspace_loc:/${ProjName}/Libraries/Lwip}&quot;"/>
+ <listOptionValue builtIn="false" value="&quot;${workspace_loc:/${ProjName}/Libraries/Lwip/lwip/src/include}&quot;"/>
+ <listOptionValue builtIn="false" value="&quot;${workspace_loc:/${ProjName}/Libraries/EMAC}&quot;"/>
+ </option>
+ <option id="gnu.c.compiler.option.preprocessor.def.symbols.571434619" name="Defined symbols (-D)" superClass="gnu.c.compiler.option.preprocessor.def.symbols" 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"/>
+ </tool>
+ <tool id="cdt.managedbuild.tool.gnu.cross.c.linker.831729502" name="Cross GCC Linker" superClass="cdt.managedbuild.tool.gnu.cross.c.linker"/>
+ <tool id="cdt.managedbuild.tool.gnu.cross.archiver.586905748" 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_sam3.o} ${INPUTS} ${LINK_FLAGS_2}" id="cdt.managedbuild.tool.gnu.cross.cpp.linker.77650722" name="Cross G++ Linker" superClass="cdt.managedbuild.tool.gnu.cross.cpp.linker">
+ <option id="gnu.cpp.link.option.nostdlibs.296038599" name="No startup or default libs (-nostdlib)" superClass="gnu.cpp.link.option.nostdlibs" value="false" valueType="boolean"/>
+ <option id="gnu.cpp.link.option.paths.75045718" 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.1995000942" name="Libraries (-l)" superClass="gnu.cpp.link.option.libs" valueType="libs">
+ <listOptionValue builtIn="false" value="${CoreName}"/>
+ </option>
+ <option id="gnu.cpp.link.option.flags.1670739910" name="Linker flags" superClass="gnu.cpp.link.option.flags" value="-Os -Wl,--gc-sections -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.1491196930" 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.1261470824" name="Cross G++ Compiler" superClass="cdt.managedbuild.tool.gnu.cross.cpp.compiler">
+ <option id="gnu.cpp.compiler.option.optimization.level.1078688101" name="Optimization Level" superClass="gnu.cpp.compiler.option.optimization.level" value="gnu.cpp.compiler.optimization.level.more" valueType="enumerated"/>
+ <option id="gnu.cpp.compiler.option.debugging.level.1332396113" name="Debug Level" superClass="gnu.cpp.compiler.option.debugging.level" value="gnu.cpp.compiler.debugging.level.none" valueType="enumerated"/>
+ <option id="gnu.cpp.compiler.option.other.verbose.1151170522" name="Verbose (-v)" superClass="gnu.cpp.compiler.option.other.verbose" value="false" valueType="boolean"/>
+ <option id="gnu.cpp.compiler.option.other.other.184134051" name="Other flags" superClass="gnu.cpp.compiler.option.other.other" 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.1285689288" name="Include paths (-I)" superClass="gnu.cpp.compiler.option.include.paths" valueType="includePath">
+ <listOptionValue builtIn="false" value="&quot;${workspace_loc:/${CoreName}/cores/arduino}&quot;"/>
+ <listOptionValue builtIn="false" value="&quot;${workspace_loc:/${CoreName}/asf}&quot;"/>
+ <listOptionValue builtIn="false" value="&quot;${workspace_loc:/${CoreName}/asf/common/utils}&quot;"/>
+ <listOptionValue builtIn="false" value="&quot;${workspace_loc:/${CoreName}/asf/sam/utils}&quot;"/>
+ <listOptionValue builtIn="false" value="&quot;${workspace_loc:/${CoreName}/asf/sam/utils/cmsis/sam3x/include}&quot;"/>
+ <listOptionValue builtIn="false" value="&quot;${workspace_loc:/${CoreName}/asf/sam/utils/cmsis/sam3x/source/templates}&quot;"/>
+ <listOptionValue builtIn="false" value="&quot;${workspace_loc:/${CoreName}/asf/sam/utils/header_files}&quot;"/>
+ <listOptionValue builtIn="false" value="&quot;${workspace_loc:/${CoreName}/asf/thirdparty/CMSIS/Include}&quot;"/>
+ <listOptionValue builtIn="false" value="&quot;${workspace_loc:/${CoreName}/variants/duet}&quot;"/>
+ <listOptionValue builtIn="false" value="&quot;${workspace_loc:/${ProjName}/Libraries/Lwip}&quot;"/>
+ <listOptionValue builtIn="false" value="&quot;${workspace_loc:/${ProjName}/Libraries/EMAC}&quot;"/>
+ <listOptionValue builtIn="false" value="&quot;${workspace_loc:/${ProjName}/Libraries/SD_HSMCI}&quot;"/>
+ <listOptionValue builtIn="false" value="&quot;${workspace_loc:/${ProjName}/Libraries/SD_HSMCI/utility}&quot;"/>
+ <listOptionValue builtIn="false" value="&quot;${workspace_loc:/${ProjName}/Libraries/SPI}&quot;"/>
+ <listOptionValue builtIn="false" value="&quot;${workspace_loc:/${ProjName}/Libraries/MAX31855}&quot;"/>
+ <listOptionValue builtIn="false" value="&quot;${workspace_loc:/${ProjName}/Libraries/MCP4461}&quot;"/>
+ <listOptionValue builtIn="false" value="&quot;${workspace_loc:/${ProjName}/Libraries/Flash}&quot;"/>
+ <listOptionValue builtIn="false" value="&quot;${workspace_loc:/${ProjName}/Libraries/Wire}&quot;"/>
+ </option>
+ <option id="gnu.cpp.compiler.option.preprocessor.def.1548770846" name="Defined symbols (-D)" superClass="gnu.cpp.compiler.option.preprocessor.def" 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"/>
+ </tool>
+ </toolChain>
+ </folderInfo>
+ <sourceEntries>
+ <entry excluding="Libraries/Lwip/lwip/src/core/ipv6|Libraries/Lwip/lwip/test|DuetArduinoCore/system/CMSIS/Device/ATMEL/sam3xa/source/as_gcc|DuetArduinoCore/system/CMSIS/Device/ATMEL/sam3xa/source/gcc_atmel|DuetArduinoCore/system/CMSIS/Device/ARM|DuetArduinoCore/system/CMSIS/Device/ATMEL/sam3xa/source/gcc_arm|DuetArduinoCore/system/CMSIS/Device/ATMEL/sam3xa/source/iar|DuetArduinoCore/system/CMSIS/CMSIS/Lib/ARM|DuetArduinoCore/system/CMSIS/CMSIS/DSP_Lib|DuetArduinoCore/system/CMSIS/Device/ATMEL/sam4.h|DuetArduinoCore/system/CMSIS/Device/ATMEL/sam4s|DuetArduinoCore/system/CMSIS/Device/ATMEL/sam3u|DuetArduinoCore/system/CMSIS/Device/ATMEL/sam3s|DuetArduinoCore/system/CMSIS/Device/ATMEL/sam3n|DuetArduinoCore/system/CMSIS/Device/ARM/ARMCM4|DuetArduinoCore/system/CMSIS/Device/ARM/ARMCM0|DuetArduinoCore/system/CMSIS/Device/ATMEL/sam3sd8" flags="VALUE_WORKSPACE_PATH|RESOLVED" kind="sourcePath" name=""/>
+ </sourceEntries>
+ </configuration>
+ </storageModule>
+ <storageModule moduleId="org.eclipse.cdt.core.externalSettings"/>
+ </cconfiguration>
</storageModule>
<storageModule moduleId="cdtBuildSystem" version="4.0.0">
<project id="RepRapFirmware.cdt.managedbuild.target.gnu.cross.exe.1494358155" name="Executable" projectType="cdt.managedbuild.target.gnu.cross.exe"/>
@@ -119,6 +235,12 @@
<configuration configurationName="Release">
<resource resourceType="PROJECT" workspacePath="/RepRapFirmware"/>
</configuration>
+ <configuration configurationName="ReleaseWithCoreNG">
+ <resource resourceType="PROJECT" workspacePath="/RepRapFirmware"/>
+ </configuration>
+ <configuration configurationName="ReleaseWithCoreDuet">
+ <resource resourceType="PROJECT" workspacePath="/RepRapFirmware"/>
+ </configuration>
</storageModule>
<storageModule moduleId="org.eclipse.cdt.internal.ui.text.commentOwnerProjectMappings"/>
<storageModule moduleId="scannerConfiguration">
diff --git a/.settings/org.eclipse.cdt.core.prefs b/.settings/org.eclipse.cdt.core.prefs
index 8a12d1cd..a1fb5643 100644
--- a/.settings/org.eclipse.cdt.core.prefs
+++ b/.settings/org.eclipse.cdt.core.prefs
@@ -1,4 +1,15 @@
eclipse.preferences.version=1
+environment/project/cdt.managedbuild.config.gnu.cross.exe.release.516195201.976458850/LINK_FLAGS_1/delimiter=;
+environment/project/cdt.managedbuild.config.gnu.cross.exe.release.516195201.976458850/LINK_FLAGS_1/operation=append
+environment/project/cdt.managedbuild.config.gnu.cross.exe.release.516195201.976458850/LINK_FLAGS_1/value=-mthumb -Wl,--cref -Wl,--check-sections -Wl,--gc-sections -Wl,--entry\=Reset_Handler -Wl,--unresolved-symbols\=report-all -Wl,--warn-common -Wl,--warn-section-align -Wl,--warn-unresolved-symbols -Wl,--start-group
+environment/project/cdt.managedbuild.config.gnu.cross.exe.release.516195201.976458850/LINK_FLAGS_2/delimiter=;
+environment/project/cdt.managedbuild.config.gnu.cross.exe.release.516195201.976458850/LINK_FLAGS_2/operation=append
+environment/project/cdt.managedbuild.config.gnu.cross.exe.release.516195201.976458850/LINK_FLAGS_2/value=-Wl,--end-group -lm -gcc
+environment/project/cdt.managedbuild.config.gnu.cross.exe.release.516195201.976458850/PATH/delimiter=;
+environment/project/cdt.managedbuild.config.gnu.cross.exe.release.516195201.976458850/PATH/operation=replace
+environment/project/cdt.managedbuild.config.gnu.cross.exe.release.516195201.976458850/PATH/value=C\:/Arduino-1.5.8/hardware/tools/gcc-arm-none-eabi-4.8.3-2014q1/bin/;C\:/Program Files (x86)/Java/jre7/bin/client;C\:/Program Files (x86)/Java/jre7/bin;C\:/Program Files (x86)/Java/jre7/lib/i386;C\:\\Windows\\system32;C\:\\Windows;C\:\\Windows\\System32\\Wbem;C\:\\Windows\\System32\\WindowsPowerShell\\v1.0\\;C\:\\Program Files (x86)\\Common Files\\Sage SData\\;C\:\\Program Files (x86)\\Common Files\\Sage SBD\\;C\:\\Program Files (x86)\\GNU\\GnuPG\\pub;C\:\\Program Files (x86)\\MiKTeX 2.9\\miktex\\bin\\;C\:\\Program Files\\Microsoft SQL Server\\110\\Tools\\Binn\\;C\:\\WINDOWS\\system32;C\:\\WINDOWS;C\:\\WINDOWS\\System32\\Wbem;C\:\\WINDOWS\\System32\\WindowsPowerShell\\v1.0\\;C\:\\Program Files (x86)\\ATI Technologies\\ATI.ACE\\Core-Static;C\:\\Program Files (x86)\\AMD\\ATI.ACE\\Core-Static;C\:\\Strawberry\\c\\bin;C\:\\Strawberry\\perl\\site\\bin;C\:\\Strawberry\\perl\\bin;C\:\\Program Files\\nodejs\\;C\:\\Program Files (x86)\\Skype\\Phone\\;C\:\\Program Files (x86)\\Atmel\\sam-ba_2.15\\drv\\;C\:\\Program Files (x86)\\Atmel\\sam-ba_2.15;C\:\\SPARK\\gpl-2014\\bin;C\:\\GNAT\\2014\\bin;C\:\\Bin;C\:\\Python27;C\:\\Users\\David\\AppData\\Roaming\\npm;C\:\\eclipse-juno
+environment/project/cdt.managedbuild.config.gnu.cross.exe.release.516195201.976458850/append=true
+environment/project/cdt.managedbuild.config.gnu.cross.exe.release.516195201.976458850/appendContributed=true
environment/project/cdt.managedbuild.config.gnu.cross.exe.release.516195201/LINK_FLAGS_1/delimiter=;
environment/project/cdt.managedbuild.config.gnu.cross.exe.release.516195201/LINK_FLAGS_1/operation=append
environment/project/cdt.managedbuild.config.gnu.cross.exe.release.516195201/LINK_FLAGS_1/value=-mthumb -Wl,--cref -Wl,--check-sections -Wl,--gc-sections -Wl,--entry\=Reset_Handler -Wl,--unresolved-symbols\=report-all -Wl,--warn-common -Wl,--warn-section-align -Wl,--warn-unresolved-symbols -Wl,--start-group
diff --git a/BuildInstructions.txt b/BuildInstructions.txt
index 18af1e31..104d659e 100644
--- a/BuildInstructions.txt
+++ b/BuildInstructions.txt
@@ -15,7 +15,7 @@ Instructions for building dc42 fork of RepRapFirmware version 1.09t and later un
7. If your compiler and tools are in a folder other than C:\Arduino-1.5.8\hardware\tools\gcc-arm-none-eabi-4.8.3-2014q1\bin, configure the path to the tools in both projects. You will find this in the project settings under C/C++ Build -> Settings -> Cross Settings.
-8. Ensure there is a copy of make.ex on your PATH. If you installed Arduino 1.5.8 into C:/Arduino-1.5.8 then there will be one in C:\Arduino-1.5.8\hardware\arduino\sam\system\CMSIS\Examples\cmsis_example\gcc_arm.
+8. Ensure there is a copy of make.exe on your PATH. If you installed Arduino 1.5.8 into C:/Arduino-1.5.8 then there will be one in C:\Arduino-1.5.8\hardware\arduino\sam\system\CMSIS\Examples\cmsis_example\gcc_arm.
9. Build CoreDuet first, then RepRapFirmware.
diff --git a/Release/RepRapFirmware-1.09z-rc1-dc42.bin b/Release/RepRapFirmware-1.09z-rc1-dc42.bin
new file mode 100644
index 00000000..3e2053f3
--- /dev/null
+++ b/Release/RepRapFirmware-1.09z-rc1-dc42.bin
Binary files differ
diff --git a/SD-image/sys-CoreXY/iap.bin b/SD-image/sys-CoreXY/iap.bin
index f7949880..5ab03b14 100644
--- a/SD-image/sys-CoreXY/iap.bin
+++ b/SD-image/sys-CoreXY/iap.bin
Binary files differ
diff --git a/SD-image/sys-Fisher/iap.bin b/SD-image/sys-Fisher/iap.bin
index f7949880..5ab03b14 100644
--- a/SD-image/sys-Fisher/iap.bin
+++ b/SD-image/sys-Fisher/iap.bin
Binary files differ
diff --git a/SD-image/sys-Huxley/iap.bin b/SD-image/sys-Huxley/iap.bin
index f7949880..5ab03b14 100644
--- a/SD-image/sys-Huxley/iap.bin
+++ b/SD-image/sys-Huxley/iap.bin
Binary files differ
diff --git a/SD-image/sys-MiniKossel/NoEndstops.g b/SD-image/sys-MiniKossel/NoEndstops.g
deleted file mode 100644
index 5d611877..00000000
--- a/SD-image/sys-MiniKossel/NoEndstops.g
+++ /dev/null
@@ -1,30 +0,0 @@
-; Home without endstops
-M906 X300 Y300 Z300 ; reduce motor current to be gentle on the endstops
-G91 ; use relative positioning
-G1 S2 X320 Y320 Z320 F5000 ; move all carriages up 320mm
-G90 ; back to absolute positioning
-M906 X800 Y800 Z800 ; motor currents back to normal
-G92 X0 Y0 Z497.47 ; define position
-
-; Do 3-factor calibration to remove the endstop errors
-G1 X-117 Y-67.5 Z10 F10000 ; go to just above the first probe point to speed up probing
-G30 P0 X-117 Y-67.5 Z-99999 ; X tower
-G30 P1 X117 Y-67.5 Z-99999 ; Y tower
-G30 P2 X0 Y135 Z-99999 S3 ; Z tower, and 3-factor calibrate
-
-G1 X-117 Y-67.5 Z10 F15000 ; go to just above the first probe point to speed up probing
-G30 P0 X-117 Y-67.5 Z-99999 ; X tower
-G30 P1 X0 Y-135 Z-99999 ; between X and Y towers
-G30 P2 X117 Y-67.5 Z-99999 ; Y tower
-G30 P3 X117 Y67.5 Z-99999 ; between Y and Z towers
-G30 P4 X0 Y135 Z-99999 ; Z tower
-G30 P5 X-117 Y67.5 Z-99999 ; between Z and X towers
-G30 P6 X-65 Y37.5 Z-99999 ; half way to between Z and X towers
-G30 P7 X-65 Y-37 Z-99999 ; half way to X tower
-G30 P8 X0 Y-75 Z-99999 ; half way to between X and Y towers
-G30 P9 X65 Y-37.5 Z-99999 ; half way to Y tower
-G30 P10 X65 Y37.5 Z-99999 ; half way to between Y and Z towers
-G30 P11 X0 Y75 Z-99999 ; half way to Z tower
-G30 P12 X0 Y0 Z-99999 S6 ; centre, and 6-factor calibrate
-
-G1 X0 Y0 Z150 F15000 ; get the head out of the way of the bed
diff --git a/SD-image/sys-MiniKossel/iap.bin b/SD-image/sys-MiniKossel/iap.bin
index f7949880..5ab03b14 100644
--- a/SD-image/sys-MiniKossel/iap.bin
+++ b/SD-image/sys-MiniKossel/iap.bin
Binary files differ
diff --git a/SD-image/sys-Ormerod1/iap.bin b/SD-image/sys-Ormerod1/iap.bin
index f7949880..5ab03b14 100644
--- a/SD-image/sys-Ormerod1/iap.bin
+++ b/SD-image/sys-Ormerod1/iap.bin
Binary files differ
diff --git a/SD-image/sys-Ormerod2/iap.bin b/SD-image/sys-Ormerod2/iap.bin
index f7949880..5ab03b14 100644
--- a/SD-image/sys-Ormerod2/iap.bin
+++ b/SD-image/sys-Ormerod2/iap.bin
Binary files differ
diff --git a/src/Configuration.h b/src/Configuration.h
index f8154c00..ca752ecc 100644
--- a/src/Configuration.h
+++ b/src/Configuration.h
@@ -26,11 +26,11 @@ Licence: GPL
#define NAME "RepRapFirmware"
#ifndef VERSION
-#define VERSION "1.09x-dc42"
+#define VERSION "1.09z"
#endif
#ifndef DATE
-#define DATE "2016-03-13"
+#define DATE "2016-03-23"
#endif
#define AUTHORS "reprappro, dc42, zpl, t3p3, dnewman"
@@ -89,7 +89,7 @@ const uint8_t MAX_BAD_TEMPERATURE_COUNT = 4; // Number of bad temperature sampl
const float BAD_LOW_TEMPERATURE = -10.0; // Celsius
const float DEFAULT_TEMPERATURE_LIMIT = 300.0; // Celsius
const float HOT_END_FAN_TEMPERATURE = 45.0; // Temperature at which a thermostatic hot end fan comes on
-const float BAD_ERROR_TEMPERATURE = 2000.0; // must exceed BAD_HIGH_TEMPERATURE
+const float BAD_ERROR_TEMPERATURE = 2000.0; // must exceed DEFAULT_TEMPERATURE_LIMIT
// PWM frequencies
diff --git a/src/DDA.cpp b/src/DDA.cpp
index d8943c89..0b7496e3 100644
--- a/src/DDA.cpp
+++ b/src/DDA.cpp
@@ -80,7 +80,7 @@ void DDA::Init()
}
// Set up a real move. Return true if it represents real movement, else false.
-bool DDA::Init(const float nextMove[], EndstopChecks ce, bool doMotorMapping, FilePosition fPos)
+bool DDA::Init(const float nextMove[], float reqSpeed, EndstopChecks ce, bool doMotorMapping, FilePosition fPos)
{
// 1. Compute the new endpoints and the movement vector
const int32_t *positionNow = prev->DriveCoordinates();
@@ -269,7 +269,6 @@ bool DDA::Init(const float nextMove[], EndstopChecks ce, bool doMotorMapping, Fi
// Set the speed to the smaller of the requested and maximum speed.
// Also enforce a minimum speed of 0.5mm/sec. We need a minimum speed to avoid overflow in the movement calculations.
- float reqSpeed = nextMove[DRIVES];
if (isSpecialDeltaMove)
{
// Special case of a raw or homing move on a delta printer
diff --git a/src/DDA.h b/src/DDA.h
index 14054650..8e030e98 100644
--- a/src/DDA.h
+++ b/src/DDA.h
@@ -30,7 +30,7 @@ public:
DDA(DDA* n);
- bool Init(const float nextMove[], EndstopChecks ce,
+ bool Init(const float nextMove[], float reqSpeed, EndstopChecks ce,
bool doMotorMapping, FilePosition fPos); // Set up a new move, returning true if it represents real movement
void Init(); // Set up initial positions for machine startup
bool Start(uint32_t tim); // Start executing the DDA, i.e. move the move.
diff --git a/src/FileStore.cpp b/src/FileStore.cpp
index 60fa06c8..48138de9 100644
--- a/src/FileStore.cpp
+++ b/src/FileStore.cpp
@@ -18,6 +18,7 @@ void FileStore::Init()
writing = false;
lastBufferEntry = 0;
openCount = 0;
+ closeRequested = false;
}
// Open a local file (for example on an SD card).
@@ -55,30 +56,61 @@ void FileStore::Duplicate()
platform->Message(GENERIC_MESSAGE, "Attempt to dup a non-open file.\n");
return;
}
+ irqflags_t flags = cpu_irq_save();
++openCount;
+ cpu_irq_restore(flags);
}
+// This may be called from an ISR, in which case we need to defer the close
bool FileStore::Close()
{
+ if (inInterrupt())
+ {
+ if (!inUse)
+ {
+ return false;
+ }
+
+ irqflags_t flags = cpu_irq_save();
+ if (openCount > 1)
+ {
+ --openCount;
+ }
+ else
+ {
+ closeRequested = true;
+ }
+ cpu_irq_restore(flags);
+ return true;
+ }
+
if (!inUse)
{
platform->Message(GENERIC_MESSAGE, "Attempt to close a non-open file.\n");
return false;
}
+
+ irqflags_t flags = cpu_irq_save();
--openCount;
- if (openCount != 0)
+ bool leaveOpen = (openCount != 0);
+ cpu_irq_restore(flags);
+
+ if (leaveOpen)
{
return true;
}
+
bool ok = true;
if (writing)
{
ok = Flush();
}
+
FRESULT fr = f_close(&file);
inUse = false;
writing = false;
lastBufferEntry = 0;
+ closeRequested = false;
return ok && fr == FR_OK;
}
@@ -157,7 +189,7 @@ uint8_t FileStore::Status()
bool FileStore::ReadBuffer()
{
FRESULT readStatus = f_read(&file, GetBuffer(), FileBufLen, &lastBufferEntry); // Read a chunk of file
- if (readStatus)
+ if (readStatus != FR_OK)
{
platform->Message(GENERIC_MESSAGE, "Error reading file.\n");
return false;
@@ -197,7 +229,7 @@ bool FileStore::Read(char& b)
}
// Block read, doesn't use the buffer
-int FileStore::Read(char* extBuf, unsigned int nBytes)
+int FileStore::Read(char* extBuf, size_t nBytes)
{
if (!inUse)
{
@@ -266,7 +298,7 @@ bool FileStore::Write(const char* b)
}
// Direct block write that bypasses the buffer. Used when uploading files.
-bool FileStore::Write(const char *s, unsigned int len)
+bool FileStore::Write(const char *s, size_t len)
{
if (!inUse)
{
@@ -285,7 +317,7 @@ bool FileStore::Write(const char *s, unsigned int len)
//extern "C" uint32_t numRead, numWrite;
//uint32_t maxRead, maxWrite;
-bool FileStore::InternalWriteBlock(const char *s, unsigned int len)
+bool FileStore::InternalWriteBlock(const char *s, size_t len)
{
unsigned int bytesWritten;
uint32_t time = micros();
diff --git a/src/FileStore.h b/src/FileStore.h
index ad1dc496..f64d941b 100644
--- a/src/FileStore.h
+++ b/src/FileStore.h
@@ -22,9 +22,9 @@ public:
uint8_t Status(); // Returns OR of IOStatus
bool Read(char& b); // Read 1 byte
- int Read(char* buf, unsigned int nBytes); // Read a block of nBytes length
+ int Read(char* buf, size_t nBytes); // Read a block of nBytes length
bool Write(char b); // Write 1 byte
- bool Write(const char *s, unsigned int len); // Write a block of len bytes
+ bool Write(const char *s, size_t len); // Write a block of len bytes
bool Write(const char* s); // Write a string
bool Close(); // Shut the file and tidy up
bool Seek(FilePosition pos); // Jump to pos in the file
@@ -49,8 +49,8 @@ protected:
private:
bool ReadBuffer();
bool WriteBuffer();
- bool InternalWriteBlock(const char *s, unsigned int len);
- byte *GetBuffer() { return reinterpret_cast<byte*>(buf32); }
+ bool InternalWriteBlock(const char *s, size_t len);
+ uint8_t *GetBuffer() { return reinterpret_cast<uint8_t*>(buf32); }
uint32_t buf32[FileBufLen/4];
Platform* platform;
@@ -58,7 +58,8 @@ private:
FIL file;
unsigned int lastBufferEntry;
- unsigned int openCount;
+ volatile unsigned int openCount;
+ volatile bool closeRequested;
bool inUse;
bool writing;
diff --git a/src/GCodeBuffer.cpp b/src/GCodeBuffer.cpp
index be8538b3..08b607d4 100644
--- a/src/GCodeBuffer.cpp
+++ b/src/GCodeBuffer.cpp
@@ -53,7 +53,7 @@ bool GCodeBuffer::Put(char c)
else if (c == '\n' || c == 0)
{
gcodeBuffer[gcodePointer] = 0;
- if (reprap.Debug(moduleGcodes) && gcodeBuffer[0] && !writingFileDirectory) // Don't bother with blank/comment lines
+ if (reprap.Debug(moduleGcodes) && gcodeBuffer[0] != 0 && !writingFileDirectory) // Don't bother with blank/comment lines
{
platform->MessageF(HOST_MESSAGE, "%s%s\n", identity, gcodeBuffer);
}
@@ -304,12 +304,12 @@ const char* GCodeBuffer::GetString()
const char* GCodeBuffer::GetUnprecedentedString(bool optional)
{
readPointer = 0;
- while (gcodeBuffer[readPointer] && gcodeBuffer[readPointer] != ' ')
+ while (gcodeBuffer[readPointer] != 0 && gcodeBuffer[readPointer] != ' ')
{
readPointer++;
}
- if (!gcodeBuffer[readPointer])
+ if (gcodeBuffer[readPointer] == 0)
{
readPointer = -1;
if (optional)
diff --git a/src/GCodes.cpp b/src/GCodes.cpp
index 887a3cf8..9ff398d5 100644
--- a/src/GCodes.cpp
+++ b/src/GCodes.cpp
@@ -33,7 +33,7 @@ const char GCodes::axisLetters[AXES] =
const size_t gcodeReplyLength = 2048; // long enough to pass back a reasonable number of files in response to M20
GCodes::GCodes(Platform* p, Webserver* w) :
- platform(p), active(false), webserver(w), stackPointer(0), auxGCodeReply(nullptr), isFlashing(false)
+ platform(p), webserver(w), active(false), stackPointer(0), auxGCodeReply(nullptr), isFlashing(false)
{
httpGCode = new GCodeBuffer(platform, "web: ");
telnetGCode = new GCodeBuffer(platform, "telnet: ");
@@ -45,7 +45,7 @@ GCodes::GCodes(Platform* p, Webserver* w) :
void GCodes::Exit()
{
- platform->Message(GENERIC_MESSAGE, "GCodes class exited.\n");
+ platform->Message(HOST_MESSAGE, "GCodes class exited.\n");
active = false;
}
@@ -77,6 +77,8 @@ void GCodes::Init()
{
pausedFanValues[i] = 0.0;
}
+
+ retractLength = retractExtra = retractSpeed = retractHop = 0.0;
}
// This is called from Init and when doing an emergency stop
@@ -93,7 +95,6 @@ void GCodes::Reset()
fileBeingPrinted.Close();
fileToPrint.Close();
fileBeingWritten = NULL;
- endStopsToCheck = 0;
doingFileMacro = false;
dwellWaiting = false;
stackPointer = 0;
@@ -104,17 +105,17 @@ void GCodes::Reset()
cannedCycleMoveCount = 0;
cannedCycleMoveQueued = false;
speedFactor = 1.0 / minutesToSeconds; // default is just to convert from mm/minute to mm/second
- speedFactorChange = 1.0;
for (size_t i = 0; i < DRIVES - AXES; ++i)
{
extrusionFactors[i] = 1.0;
}
for (size_t i = 0; i < DRIVES; ++i)
{
- moveBuffer[i] = 0.0;
+ moveBuffer.coords[i] = 0.0;
pausedMoveBuffer[i] = 0.0;
}
- moveBuffer[DRIVES] = DEFAULT_FEEDRATE/minutesToSeconds;
+ feedRate = pausedMoveBuffer[DRIVES] = DEFAULT_FEEDRATE/minutesToSeconds;
+ ClearMove();
auxDetected = false;
while (auxGCodeReply != nullptr)
@@ -125,7 +126,7 @@ void GCodes::Reset()
simulating = false;
simulationTime = 0.0;
isPaused = false;
- filePos = moveFilePos = noFilePosition;
+ filePos = moveBuffer.filePos = noFilePosition;
}
float GCodes::FractionOfFilePrinted() const
@@ -343,23 +344,23 @@ void GCodes::Spin()
// Move the head back to the paused location
if (AllMovesAreFinishedAndMoveBufferIsLoaded())
{
- float currentZ = moveBuffer[Z_AXIS];
+ float currentZ = moveBuffer.coords[Z_AXIS];
for (size_t drive = 0; drive < AXES; ++drive)
{
- moveBuffer[drive] = pausedMoveBuffer[drive];
+ moveBuffer.coords[drive] = pausedMoveBuffer[drive];
}
for (size_t drive = AXES; drive < DRIVES; ++drive)
{
- moveBuffer[drive] = 0.0;
+ moveBuffer.coords[drive] = 0.0;
}
- moveBuffer[DRIVES] = DEFAULT_FEEDRATE/minutesToSeconds; // ask for a good feed rate, we may have paused during a slow move
- moveType = 0;
- endStopsToCheck = 0;
- moveFilePos = noFilePosition;
+ 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.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[Z_AXIS] = currentZ;
+ moveBuffer.coords[Z_AXIS] = currentZ;
state = GCodeState::resuming2;
}
else
@@ -383,8 +384,7 @@ void GCodes::Spin()
{
lastRawExtruderPosition[drive - AXES] = pausedMoveBuffer[drive]; // reset the extruder position in case we are receiving absolute extruder moves
}
- moveBuffer[DRIVES] = pausedMoveBuffer[DRIVES];
- reprap.GetMove()->SetFeedrate(pausedMoveBuffer[DRIVES]);
+ feedRate = pausedMoveBuffer[DRIVES];
fileGCode->Resume();
isPaused = false;
HandleReply(gbCurrent, false, "Printing resumed");
@@ -567,12 +567,12 @@ bool GCodes::AllMovesAreFinishedAndMoveBufferIsLoaded()
if (moveAvailable)
return false;
- // Wait for all the queued moves to stop so we get the actual last position and feedrate
+ // Wait for all the queued moves to stop so we get the actual last position
if (!reprap.GetMove()->AllMovesAreFinished())
return false;
reprap.GetMove()->ResumeMoving();
- reprap.GetMove()->GetCurrentUserPosition(moveBuffer, 0);
+ reprap.GetMove()->GetCurrentUserPosition(moveBuffer.coords, 0);
return true;
}
@@ -587,7 +587,7 @@ void GCodes::Push()
stack[stackPointer].state = state;
stack[stackPointer].gb = gbCurrent;
- stack[stackPointer].feedrate = moveBuffer[DRIVES];
+ stack[stackPointer].feedrate = feedRate;
stack[stackPointer].fileState.CopyFrom(fileBeingPrinted);
stack[stackPointer].drivesRelative = drivesRelative;
stack[stackPointer].axesRelative = axesRelative;
@@ -607,8 +607,7 @@ void GCodes::Pop()
stackPointer--;
state = stack[stackPointer].state;
gbCurrent = stack[stackPointer].gb;
- moveBuffer[DRIVES] = stack[stackPointer].feedrate;
- reprap.GetMove()->SetFeedrate(moveBuffer[DRIVES]);
+ feedRate = stack[stackPointer].feedrate;
fileBeingPrinted.MoveFrom(stack[stackPointer].fileState);
drivesRelative = stack[stackPointer].drivesRelative;
axesRelative = stack[stackPointer].axesRelative;
@@ -624,14 +623,15 @@ bool GCodes::LoadMoveBufferFromGCode(GCodeBuffer *gb, bool doingG92, bool applyL
// Zero every extruder drive as some drives may not be changed
for (size_t drive = AXES; drive < DRIVES; drive++)
{
- moveBuffer[drive] = 0.0;
+ moveBuffer.coords[drive] = 0.0;
}
// Deal with feed rate
if (gb->Seen(feedrateLetter))
{
- moveBuffer[DRIVES] = gb->GetFValue() * distanceScale * speedFactor;
+ feedRate = gb->GetFValue() * distanceScale * speedFactor;
}
+ moveBuffer.feedRate = feedRate;
// First do extrusion, and check, if we are extruding, that we have a tool to extrude with
Tool* tool = reprap.GetCurrentTool();
@@ -646,7 +646,7 @@ bool GCodes::LoadMoveBufferFromGCode(GCodeBuffer *gb, bool doingG92, bool applyL
if (eMoveCount > 0)
{
float eMovement[DRIVES - AXES];
- if (tool->Mixing())
+ if (tool->GetMixing())
{
float length = gb->GetFValue();
for (size_t drive = 0; drive < tool->DriveCount(); drive++)
@@ -673,7 +673,7 @@ bool GCodes::LoadMoveBufferFromGCode(GCodeBuffer *gb, bool doingG92, bool applyL
float moveArg = eMovement[eDrive] * distanceScale;
if (doingG92)
{
- moveBuffer[drive + AXES] = 0.0; // no move required
+ moveBuffer.coords[drive + AXES] = 0.0; // no move required
lastRawExtruderPosition[drive] = moveArg;
}
else
@@ -684,7 +684,7 @@ bool GCodes::LoadMoveBufferFromGCode(GCodeBuffer *gb, bool doingG92, bool applyL
lastRawExtruderPosition[drive] += extrusionAmount;
rawExtruderTotalByDrive[drive] += extrusionAmount;
rawExtruderTotal += extrusionAmount;
- moveBuffer[drive + AXES] = extrusionAmount * extrusionFactors[drive];
+ moveBuffer.coords[drive + AXES] = extrusionAmount * extrusionFactors[drive];
}
}
}
@@ -705,7 +705,7 @@ bool GCodes::LoadMoveBufferFromGCode(GCodeBuffer *gb, bool doingG92, bool applyL
{
if (axesRelative)
{
- moveArg += moveBuffer[axis];
+ moveArg += moveBuffer.coords[axis];
}
else if (currentTool != NULL)
{
@@ -729,7 +729,7 @@ bool GCodes::LoadMoveBufferFromGCode(GCodeBuffer *gb, bool doingG92, bool applyL
}
}
}
- moveBuffer[axis] = moveArg;
+ moveBuffer.coords[axis] = moveArg;
}
}
@@ -738,17 +738,17 @@ bool GCodes::LoadMoveBufferFromGCode(GCodeBuffer *gb, bool doingG92, bool applyL
if (applyLimits && reprap.GetMove()->IsDeltaMode() && AllAxesAreHomed())
{
// Constrain the move to be within the build radius
- float diagonalSquared = fsquare(moveBuffer[X_AXIS]) + fsquare(moveBuffer[Y_AXIS]);
+ float diagonalSquared = fsquare(moveBuffer.coords[X_AXIS]) + fsquare(moveBuffer.coords[Y_AXIS]);
if (diagonalSquared > reprap.GetMove()->GetDeltaParams().GetPrintRadiusSquared())
{
float factor = sqrtf(reprap.GetMove()->GetDeltaParams().GetPrintRadiusSquared() / diagonalSquared);
- moveBuffer[X_AXIS] *= factor;
- moveBuffer[Y_AXIS] *= factor;
+ moveBuffer.coords[X_AXIS] *= factor;
+ moveBuffer.coords[Y_AXIS] *= factor;
}
// Constrain the end height of the move to be no greater than the homed height and no lower than -0.2mm
- moveBuffer[Z_AXIS] = max<float>(platform->AxisMinimum(Z_AXIS),
- min<float>(moveBuffer[Z_AXIS], reprap.GetMove()->GetDeltaParams().GetHomedHeight()));
+ moveBuffer.coords[Z_AXIS] = max<float>(platform->AxisMinimum(Z_AXIS),
+ min<float>(moveBuffer.coords[Z_AXIS], reprap.GetMove()->GetDeltaParams().GetHomedHeight()));
}
return true;
@@ -768,14 +768,14 @@ int GCodes::SetUpMove(GCodeBuffer *gb, StringRef& reply)
}
// Check to see if the move is a 'homing' move that endstops are checked on.
- endStopsToCheck = 0;
- moveType = 0;
+ moveBuffer.endStopsToCheck = 0;
+ moveBuffer.moveType = 0;
if (gb->Seen('S'))
{
int ival = gb->GetIValue();
if (ival == 1 || ival == 2)
{
- moveType = ival;
+ moveBuffer.moveType = ival;
}
if (ival == 1)
@@ -784,7 +784,7 @@ int GCodes::SetUpMove(GCodeBuffer *gb, StringRef& reply)
{
if (gb->Seen(axisLetters[i]))
{
- endStopsToCheck |= (1 << i);
+ moveBuffer.endStopsToCheck |= (1 << i);
}
}
}
@@ -793,7 +793,7 @@ int GCodes::SetUpMove(GCodeBuffer *gb, StringRef& reply)
if (reprap.GetMove()->IsDeltaMode())
{
// Extra checks to avoid damaging delta printers
- if (moveType != 0 && !axesRelative)
+ if (moveBuffer.moveType != 0 && !axesRelative)
{
// We have been asked to do a move without delta mapping on a delta machine, but the move is not relative.
// This may be damaging and is almost certainly a user mistake, so ignore the move.
@@ -801,7 +801,7 @@ int GCodes::SetUpMove(GCodeBuffer *gb, StringRef& reply)
return 1;
}
- if (moveType == 0 && !AllAxesAreHomed())
+ if (moveBuffer.moveType == 0 && !AllAxesAreHomed())
{
// The user may be attempting to move a delta printer to an XYZ position before homing the axes
// This may be damaging and is almost certainly a user mistake, so ignore the move. But allow extruder-only moves.
@@ -822,38 +822,29 @@ int GCodes::SetUpMove(GCodeBuffer *gb, StringRef& reply)
else
#endif
{
- reprap.GetMove()->GetCurrentUserPosition(moveBuffer, moveType);
+ reprap.GetMove()->GetCurrentUserPosition(moveBuffer.coords, moveBuffer.moveType);
}
- moveBuffer[DRIVES] *= speedFactorChange; // account for any change in the speed factor since the last move
- speedFactorChange = 1.0;
-
// Load the move buffer with either the absolute movement required or the relative movement required
- moveAvailable = LoadMoveBufferFromGCode(gb, false, limitAxes && moveType == 0);
+ moveAvailable = LoadMoveBufferFromGCode(gb, false, limitAxes && moveBuffer.moveType == 0);
if (moveAvailable)
{
- moveFilePos = (gb == fileGCode) ? filePos : noFilePosition;
+ moveBuffer.filePos = (gb == fileGCode) ? filePos : noFilePosition;
//debugPrintf("Queue move pos %u\n", moveFilePos);
}
- return (moveType != 0) ? 2 : 1;
+ return (moveBuffer.moveType != 0) ? 2 : 1;
}
// The Move class calls this function to find what to do next.
-bool GCodes::ReadMove(float m[], EndstopChecks& ce, uint8_t& rMoveType, FilePosition& fPos)
+bool GCodes::ReadMove(RawMove& m)
{
if (!moveAvailable)
{
return false;
}
- for (size_t i = 0; i <= DRIVES; i++) // 1 more for feedrate
- {
- m[i] = moveBuffer[i];
- }
- ce = endStopsToCheck;
- rMoveType = moveType;
- fPos = moveFilePos;
+ m = moveBuffer;
ClearMove();
return true;
}
@@ -861,8 +852,9 @@ bool GCodes::ReadMove(float m[], EndstopChecks& ce, uint8_t& rMoveType, FilePosi
void GCodes::ClearMove()
{
moveAvailable = false;
- endStopsToCheck = 0;
- moveType = 0;
+ moveBuffer.endStopsToCheck = 0;
+ moveBuffer.moveType = 0;
+ moveBuffer.isFirmwareRetraction = false;
}
// Run a file macro. Prior to calling this, 'state' must be set to the state we want to enter when the macro has been completed.
@@ -916,14 +908,16 @@ bool GCodes::DoCannedCycleMove(EndstopChecks ce)
// Otherwise, the move has not been queued yet
Push();
- for (size_t drive = 0; drive <= DRIVES; drive++)
+ for (size_t drive = 0; drive < DRIVES; drive++)
{
if (activeDrive[drive])
{
- moveBuffer[drive] = moveToDo[drive];
+ moveBuffer.coords[drive] = moveToDo[drive];
}
}
- endStopsToCheck = ce;
+ moveBuffer.feedRate = moveToDo[DRIVES];
+ moveBuffer.endStopsToCheck = ce;
+ moveBuffer.filePos = noFilePosition;
cannedCycleMoveQueued = true;
moveAvailable = true;
}
@@ -957,7 +951,7 @@ bool GCodes::SetPositions(GCodeBuffer *gb)
return false;
}
- reprap.GetMove()->GetCurrentUserPosition(moveBuffer, 0); // make sure move buffer is up to date
+ reprap.GetMove()->GetCurrentUserPosition(moveBuffer.coords, 0); // make sure move buffer is up to date
bool ok = LoadMoveBufferFromGCode(gb, true, false);
if (ok && includingAxes)
{
@@ -973,7 +967,7 @@ bool GCodes::SetPositions(GCodeBuffer *gb)
}
}
#endif
- SetPositions(moveBuffer);
+ SetPositions(moveBuffer.coords);
}
return true;
@@ -987,13 +981,15 @@ bool GCodes::OffsetAxes(GCodeBuffer* gb)
if (!offSetSet)
{
if (!AllMovesAreFinishedAndMoveBufferIsLoaded())
+ {
return false;
- for (size_t drive = 0; drive <= DRIVES; drive++)
+ }
+ for (size_t drive = 0; drive < DRIVES; drive++)
{
- if (drive < AXES || drive == DRIVES)
+ if (drive < AXES)
{
- record[drive] = moveBuffer[drive];
- moveToDo[drive] = moveBuffer[drive];
+ record[drive] = moveBuffer.coords[drive];
+ moveToDo[drive] = moveBuffer.coords[drive];
}
else
{
@@ -1002,6 +998,7 @@ bool GCodes::OffsetAxes(GCodeBuffer* gb)
}
activeDrive[drive] = false;
}
+ record[DRIVES] = moveToDo[DRIVES] = feedRate;
for (size_t axis = 0; axis < AXES; axis++)
{
@@ -1023,10 +1020,10 @@ bool GCodes::OffsetAxes(GCodeBuffer* gb)
if (DoCannedCycleMove(0))
{
- //LoadMoveBufferFromArray(record);
- for (size_t drive = 0; drive <= DRIVES; drive++)
+ // Restore positions
+ for (size_t drive = 0; drive < DRIVES; drive++)
{
- moveBuffer[drive] = record[drive];
+ moveBuffer.coords[drive] = record[drive];
}
reprap.GetMove()->SetLiveCoordinates(record); // This doesn't transform record
reprap.GetMove()->SetPositions(record); // This does
@@ -1163,13 +1160,13 @@ bool GCodes::DoSingleZProbeAtPoint(int probePointIndex, float heightAdjust)
case 1:
if (axisIsHomed[Z_AXIS])
{
- lastProbedZ = moveBuffer[Z_AXIS] - (platform->ZProbeStopHeight() + heightAdjust);
+ lastProbedZ = moveBuffer.coords[Z_AXIS] - (platform->ZProbeStopHeight() + heightAdjust);
}
else
{
// The Z axis has not yet been homed, so treat this probe as a homing move.
- moveBuffer[Z_AXIS] = platform->ZProbeStopHeight() + heightAdjust;
- SetPositions(moveBuffer);
+ moveBuffer.coords[Z_AXIS] = platform->ZProbeStopHeight() + heightAdjust;
+ SetPositions(moveBuffer.coords);
axisIsHomed[Z_AXIS] = true;
lastProbedZ = 0.0;
}
@@ -1213,8 +1210,8 @@ bool GCodes::DoSingleZProbe(bool reportOnly, float heightAdjust)
case 1: // success
if (!reportOnly)
{
- moveBuffer[Z_AXIS] = platform->ZProbeStopHeight() + heightAdjust;
- SetPositions(moveBuffer);
+ moveBuffer.coords[Z_AXIS] = platform->ZProbeStopHeight() + heightAdjust;
+ SetPositions(moveBuffer.coords);
axisIsHomed[Z_AXIS] = true;
lastProbedZ = 0.0;
}
@@ -1302,9 +1299,9 @@ bool GCodes::SetSingleZProbeAtAPosition(GCodeBuffer *gb, StringRef& reply)
return true;
}
- float x = (gb->Seen(axisLetters[X_AXIS])) ? gb->GetFValue() : moveBuffer[X_AXIS];
- float y = (gb->Seen(axisLetters[Y_AXIS])) ? gb->GetFValue() : moveBuffer[Y_AXIS];
- float z = (gb->Seen(axisLetters[Z_AXIS])) ? gb->GetFValue() : moveBuffer[Z_AXIS];
+ float x = (gb->Seen(axisLetters[X_AXIS])) ? gb->GetFValue() : moveBuffer.coords[X_AXIS];
+ float y = (gb->Seen(axisLetters[Y_AXIS])) ? gb->GetFValue() : moveBuffer.coords[Y_AXIS];
+ float z = (gb->Seen(axisLetters[Z_AXIS])) ? gb->GetFValue() : moveBuffer.coords[Z_AXIS];
reprap.GetMove()->SetXBedProbePoint(probePointIndex, x);
reprap.GetMove()->SetYBedProbePoint(probePointIndex, y);
@@ -1331,8 +1328,8 @@ bool GCodes::SetSingleZProbeAtAPosition(GCodeBuffer *gb, StringRef& reply)
{
// G30 with a silly Z value and S=1 is equivalent to G30 with no parameters in that it sets the current Z height
// This is useful because it adjusts the XY position to account for the probe offset.
- moveBuffer[Z_AXIS] += lastProbedZ;
- SetPositions(moveBuffer);
+ moveBuffer.coords[Z_AXIS] += lastProbedZ;
+ SetPositions(moveBuffer.coords);
lastProbedZ = 0.0;
}
else
@@ -2316,10 +2313,46 @@ void GCodes::SetToolHeaters(Tool *tool, float temperature)
tool->SetVariables(standby, active);
}
+// Retract or un-retract filament, returning true if movement has been queued, false if this needs to be called again
+bool GCodes::RetractFilament(bool retract)
+{
+ if (retractLength != 0.0 || retractHop != 0.0 || (retract && retractExtra != 0.0))
+ {
+ const Tool *tool = reprap.GetCurrentTool();
+ if (tool != nullptr)
+ {
+ size_t nDrives = tool->DriveCount();
+ if (nDrives != 0)
+ {
+ if (moveAvailable)
+ {
+ return false;
+ }
+
+ reprap.GetMove()->GetCurrentUserPosition(moveBuffer.coords, 0);
+ for (size_t i = AXES; i < DRIVES; ++i)
+ {
+ moveBuffer.coords[i] = 0.0;
+ }
+ moveBuffer.feedRate = retractSpeed * secondsToMinutes; // set the feed rate
+ moveBuffer.coords[Z_AXIS] += ((retract) ? retractHop : -retractHop);
+ for (size_t i = 0; i < nDrives; ++i)
+ {
+ moveBuffer.coords[E0_AXIS + tool->Drive(i)] = (retract) ? -retractLength : retractLength + retractExtra;
+ }
+
+ moveBuffer.isFirmwareRetraction = true;
+ moveBuffer.filePos = filePos;
+ moveAvailable = true;
+ }
+ }
+ }
+ return true;
+}
+
// If the code to act on is completed, this returns true,
// otherwise false. It is called repeatedly for a given
// code until it returns true for that code.
-
bool GCodes::ActOnCode(GCodeBuffer *gb, StringRef& reply)
{
// Discard empty buffers right away
@@ -2378,16 +2411,17 @@ bool GCodes::HandleGcode(GCodeBuffer* gb, StringRef& reply)
for (size_t axis = 0; axis < AXES; ++axis)
{
float offset = gb->Seen(axisLetters[axis]) ? gb->GetFValue() * distanceScale : 0.0;
- moveBuffer[axis] = pausedMoveBuffer[axis] + offset;
+ moveBuffer.coords[axis] = pausedMoveBuffer[axis] + offset;
}
for (size_t drive = AXES; drive < DRIVES; ++drive)
{
- moveBuffer[drive] = 0.0;
+ moveBuffer.coords[drive] = 0.0;
}
if (gb->Seen(feedrateLetter))
{
- moveBuffer[DRIVES] = gb->GetFValue();
+ moveBuffer.feedRate = (gb->Seen(feedrateLetter)) ? gb->GetFValue() : feedRate;
}
+ moveBuffer.filePos = noFilePosition;
moveAvailable = true;
}
else
@@ -2405,8 +2439,19 @@ bool GCodes::HandleGcode(GCodeBuffer* gb, StringRef& reply)
result = DoDwell(gb);
break;
- case 10: // Set/report offsets and temperatures
- SetOrReportOffsets(reply, gb);
+ case 10: // Set/report offsets and temperatures, or retract
+ if (gb->Seen('P'))
+ {
+ SetOrReportOffsets(reply, gb);
+ }
+ else
+ {
+ result = RetractFilament(true);
+ }
+ break;
+
+ case 11: // Un-retract
+ result = RetractFilament(false);
break;
case 20: // Inches (which century are we living in, here?)
@@ -2772,6 +2817,7 @@ bool GCodes::HandleMcode(GCodeBuffer* gb, StringRef& reply)
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())
{
@@ -2782,7 +2828,7 @@ bool GCodes::HandleMcode(GCodeBuffer* gb, StringRef& reply)
{
for (size_t drive = AXES; drive < DRIVES; ++drive)
{
- pausedMoveBuffer[drive] += moveBuffer[drive]; // add on the extrusion in the move not yet taken
+ pausedMoveBuffer[drive] += moveBuffer.coords[drive]; // add on the extrusion in the move not yet taken
}
ClearMove();
}
@@ -2802,13 +2848,13 @@ bool GCodes::HandleMcode(GCodeBuffer* gb, StringRef& reply)
// Pausing a file print because of a command in the file itself
for (size_t drive = 0; drive < AXES; ++drive)
{
- pausedMoveBuffer[drive] = moveBuffer[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] = moveBuffer[DRIVES];
+ pausedMoveBuffer[DRIVES] = feedRate;
}
for (size_t i = 0; i < NUM_FANS; ++i)
@@ -2937,7 +2983,11 @@ bool GCodes::HandleMcode(GCodeBuffer* gb, StringRef& reply)
{
// Ending a simulation, so restore the position
SetPositions(savedMoveBuffer);
- reprap.GetMove()->SetFeedrate(savedMoveBuffer[DRIVES]);
+ for (size_t i = 0; i < DRIVES; ++i)
+ {
+ moveBuffer.coords[i] = savedMoveBuffer[i];
+ }
+ feedRate = savedMoveBuffer[DRIVES];
}
}
else
@@ -3214,7 +3264,7 @@ bool GCodes::HandleMcode(GCodeBuffer* gb, StringRef& reply)
uint16_t hh = platform->GetHeatersMonitored(fanNum);
if (hh == 0)
{
- reply.catf("value: %d%%\n", (int)(platform->GetFanValue(fanNum) * 100.0));
+ reply.catf("value: %d%%", (int)(platform->GetFanValue(fanNum) * 100.0));
}
else
{
@@ -3553,7 +3603,16 @@ bool GCodes::HandleMcode(GCodeBuffer* gb, StringRef& reply)
case 143: // Set temperature limit
if (gb->Seen('S'))
{
- platform->SetTemperatureLimit(gb->GetFValue());
+ float limit = gb->GetFValue();
+ if (limit > BAD_LOW_TEMPERATURE && limit < BAD_ERROR_TEMPERATURE)
+ {
+ platform->SetTemperatureLimit(limit);
+ }
+ else
+ {
+ reply.copy("Invalid temperature limit");
+ error = true;
+ }
}
else
{
@@ -3587,7 +3646,7 @@ bool GCodes::HandleMcode(GCodeBuffer* gb, StringRef& reply)
}
break;
- case 201: // Set/print axis accelerations FIXME - should these be in /min not /sec ?
+ case 201: // Set/print axis accelerations
{
bool seen = false;
for (size_t axis = 0; axis < AXES; axis++)
@@ -3678,6 +3737,37 @@ bool GCodes::HandleMcode(GCodeBuffer* gb, StringRef& reply)
result = OffsetAxes(gb);
break;
+ case 207: // Set firmware retraction details
+ {
+ bool seen = false;
+ if (gb->Seen('S'))
+ {
+ retractLength = max<float>(gb->GetFValue(), 0.0);
+ seen = true;
+ }
+ if (gb->Seen('R'))
+ {
+ retractExtra = max<float>(gb->GetFValue(), 0.0);
+ seen = true;
+ }
+ if (gb->Seen('F'))
+ {
+ retractSpeed = max<float>(gb->GetFValue(), 60.0);
+ seen = true;
+ }
+ if (gb->Seen('Z'))
+ {
+ retractHop = max<float>(gb->GetFValue(), 0.0);
+ seen = true;
+ }
+ if (!seen)
+ {
+ reply.printf("Retraction settings: length %.2f, extra length %.2f, speed %d, Z hop %.2f",
+ retractLength, retractExtra, (int)retractSpeed, retractHop);
+ }
+ }
+ break;
+
case 208: // Set/print maximum axis lengths. If there is an S parameter with value 1 then we set the min value, else we set the max value.
{
bool setMin = (gb->Seen('S') ? (gb->GetIValue() == 1) : false);
@@ -3721,19 +3811,14 @@ bool GCodes::HandleMcode(GCodeBuffer* gb, StringRef& reply)
if (gb->Seen('S'))
{
float newSpeedFactor = (gb->GetFValue() / 100.0) * secondsToMinutes;// include the conversion from mm/minute to mm/second
- if (newSpeedFactor > 0)
+ if (newSpeedFactor > 0.0)
{
- float ratio = newSpeedFactor / speedFactor;
- speedFactor = newSpeedFactor;
- if (moveAvailable)
+ if (moveAvailable && !moveBuffer.isFirmwareRetraction)
{
// The last move has not gone yet, so we can update it
- moveBuffer[DRIVES] *= ratio;
- }
- else
- {
- speedFactorChange *= ratio;
+ moveBuffer.feedRate *= newSpeedFactor / speedFactor;
}
+ speedFactor = newSpeedFactor;
}
else
{
@@ -3758,11 +3843,11 @@ bool GCodes::HandleMcode(GCodeBuffer* gb, StringRef& reply)
if (gb->Seen('S')) // S parameter sets the override percentage
{
float extrusionFactor = gb->GetFValue() / 100.0;
- if (extruder >= 0 && (size_t)extruder < DRIVES - AXES && extrusionFactor >= 0)
+ if (extruder >= 0 && (size_t)extruder < DRIVES - AXES && extrusionFactor >= 0.0)
{
- if (moveAvailable)
+ if (moveAvailable && !moveBuffer.isFirmwareRetraction)
{
- moveBuffer[extruder + AXES] *= extrusionFactor/extrusionFactors[extruder]; // last move not gone, so update it
+ moveBuffer.coords[extruder + AXES] *= extrusionFactor/extrusionFactors[extruder]; // last move not gone, so update it
}
extrusionFactors[extruder] = extrusionFactor;
}
@@ -4417,14 +4502,11 @@ bool GCodes::HandleMcode(GCodeBuffer* gb, StringRef& reply)
{
if (gb->Seen('S'))
{
- if (gb->GetIValue() != 0)
- {
- tool->TurnMixingOn();
- }
- else
- {
- tool->TurnMixingOff();
- }
+ tool->SetMixing(gb->GetIValue() != 0);
+ }
+ else
+ {
+ reply.printf("Tool %d mixing is %s", tool->Number(), (tool->GetMixing()) ? "enabled" : "disabled");
}
}
}
@@ -4651,7 +4733,7 @@ bool GCodes::HandleMcode(GCodeBuffer* gb, StringRef& reply)
const size_t eDrive = eDrives[extruder] + AXES;
if (eDrive < AXES || eDrive >= DRIVES)
{
- reply.copy("Invalid extruder drive specified!\n");
+ reply.copy("Invalid extruder drive specified!");
error = result = true;
break;
}
@@ -4958,7 +5040,7 @@ bool GCodes::HandleMcode(GCodeBuffer* gb, StringRef& reply)
}
isFlashing = true;
- if (!DoDwellTime(2.0))
+ if (!DoDwellTime(1.0))
{
// wait a second so all HTTP clients are notified
return false;
diff --git a/src/GCodes.h b/src/GCodes.h
index 1abe8a3c..8cd920c2 100644
--- a/src/GCodes.h
+++ b/src/GCodes.h
@@ -75,13 +75,22 @@ public:
class GCodes
{
public:
+ struct RawMove
+ {
+ float coords[DRIVES]; // new positions for the axes, amount of movement for the extruders
+ float feedRate; // feed rate of this move
+ FilePosition filePos; // offset in the file being printed that this move was read from
+ EndstopChecks endStopsToCheck; // endstops to check
+ uint8_t moveType; // the S parameter from the G0 or G1 command, 0 for a normal move
+ bool isFirmwareRetraction; // true if this is a firmware retraction/un-retraction move
+ };
GCodes(Platform* p, Webserver* w);
void Spin(); // Called in a tight loop to make this class work
void Init(); // Set it up
void Exit(); // Shut it down
void Reset(); // Reset some parameter to defaults
- bool ReadMove(float* m, EndstopChecks& ce, uint8_t& rMoveType, FilePosition& fPos); // Called by the Move class to get a movement set by the last G Code
+ bool ReadMove(RawMove& m); // Called by the Move class to get a movement set by the last G Code
void ClearMove();
void QueueFileToPrint(const char* fileName); // Open a file of G Codes to run
void DeleteFile(const char* fileName); // Does what it says
@@ -163,13 +172,11 @@ private:
void SetAllAxesNotHomed(); // Flag all axes as not homed
void SetPositions(float positionNow[DRIVES]); // Set the current position to be this
const char *TranslateEndStopResult(EndStopHit es); // Translate end stop result to text
+ bool RetractFilament(bool retract); // Retract or un-retract filaments
Platform* platform; // The RepRap machine
- bool active; // Live and running?
- bool isPaused; // true if the print has been paused
Webserver* webserver; // The webserver class
- float dwellTime; // How long a pause for a dwell (seconds)?
- bool dwellWaiting; // We are in a dwell
+
GCodeBuffer* httpGCode; // The sources...
GCodeBuffer* telnetGCode; // ...
GCodeBuffer* fileGCode; // ...
@@ -177,12 +184,15 @@ private:
GCodeBuffer* auxGCode; // this one is for the LCD display on the async serial interface
GCodeBuffer* fileMacroGCode; // ...
GCodeBuffer *gbCurrent;
+ bool active; // Live and running?
+ bool isPaused; // true if the print has been paused
+ bool dwellWaiting; // We are in a dwell
bool moveAvailable; // Have we seen a move G Code and set it up?
- float moveBuffer[DRIVES+1]; // Move coordinates; last is feed rate
- float savedMoveBuffer[DRIVES+1]; // The position and feedrate when we started the current simulation
- float pausedMoveBuffer[DRIVES+1]; // Move coordinates; last is feed rate
- EndstopChecks endStopsToCheck; // Which end stops we check them on the next move
- uint8_t moveType; // 0 = normal move, 1 = homing move, 2 = direct motor move
+ float dwellTime; // How long a pause for a dwell (seconds)?
+ float feedRate; // The feed rate of the last G0/G1 command that had an F parameter
+ RawMove moveBuffer; // Move details to pass to Move class
+ float savedMoveBuffer[DRIVES + 1]; // The position and feedrate when we started the current simulation
+ float pausedMoveBuffer[DRIVES + 1]; // Move coordinates; last is feed rate
GCodeState state; // The main state variable of the GCode state machine
bool drivesRelative;
bool axesRelative;
@@ -216,7 +226,6 @@ private:
bool axisIsHomed[AXES]; // These record which of the axes have been homed
float pausedFanValues[NUM_FANS]; // Fan speeds when the print was paused
float speedFactor; // speed factor, including the conversion from mm/min to mm/sec, normally 1/60
- float speedFactorChange; // factor by which we changed the speed factor since the last move
float extrusionFactors[DRIVES - AXES]; // extrusion factors (normally 1.0)
float lastProbedZ; // the last height at which the Z probe stopped
@@ -227,7 +236,11 @@ private:
float simulationTime;
bool isFlashing; // Is a new firmware binary going to be flashed?
FilePosition filePos; // The position we got up to in the file being printed
- FilePosition moveFilePos; // Saved version of filePos for the next real move to be processed
+
+ // Firmware retraction settings
+ float retractLength, retractExtra; // retraction length and extra length to un-retract
+ float retractSpeed; // retract speed in mm/min
+ float retractHop; // Z hop when retracting
};
//*****************************************************************************************************
diff --git a/src/MassStorage.cpp b/src/MassStorage.cpp
index 028b6fe0..9459015b 100644
--- a/src/MassStorage.cpp
+++ b/src/MassStorage.cpp
@@ -9,52 +9,45 @@ void MassStorage::Init()
{
// Initialize SD MMC stack
sd_mmc_init();
- delay(20);
- bool abort = false;
+ const size_t startTime = millis();
sd_mmc_err_t err;
do {
err = sd_mmc_check(0);
- if (err > SD_MMC_ERR_NO_CARD)
- {
- abort = true;
- delay(3000); // Wait a few seconds, so users have a chance to see the following error message
- }
- else
- {
- abort = (err == SD_MMC_ERR_NO_CARD && platform->Time() > 5.0);
- }
+ delay_ms(1);
+ } while (err != SD_MMC_OK && millis() - startTime < 5000);
+
+ if (err != SD_MMC_OK)
+ {
+ delay_ms(3000); // Wait a few seconds so users have a chance to see this
- if (abort)
+ platform->Message(HOST_MESSAGE, "Cannot initialise the SD card: ");
+ switch (err)
{
- platform->Message(HOST_MESSAGE, "Cannot initialize the SD card: ");
- switch (err)
- {
- case SD_MMC_ERR_NO_CARD:
- platform->Message(HOST_MESSAGE, "Card not found\n");
- break;
- case SD_MMC_ERR_UNUSABLE:
- platform->Message(HOST_MESSAGE, "Card is unusable, try another one\n");
- break;
- case SD_MMC_ERR_SLOT:
- platform->Message(HOST_MESSAGE, "Slot unknown\n");
- break;
- case SD_MMC_ERR_COMM:
- platform->Message(HOST_MESSAGE, "General communication error\n");
- break;
- case SD_MMC_ERR_PARAM:
- platform->Message(HOST_MESSAGE, "Illegal input parameter\n");
- break;
- case SD_MMC_ERR_WP:
- platform->Message(HOST_MESSAGE, "Card write protected\n");
- break;
- default:
- platform->MessageF(HOST_MESSAGE, "Unknown (code %d)\n", err);
- break;
- }
- return;
+ case SD_MMC_ERR_NO_CARD:
+ platform->Message(HOST_MESSAGE, "Card not found\n");
+ break;
+ case SD_MMC_ERR_UNUSABLE:
+ platform->Message(HOST_MESSAGE, "Card is unusable, try another one\n");
+ break;
+ case SD_MMC_ERR_SLOT:
+ platform->Message(HOST_MESSAGE, "Slot unknown\n");
+ break;
+ case SD_MMC_ERR_COMM:
+ platform->Message(HOST_MESSAGE, "General communication error\n");
+ break;
+ case SD_MMC_ERR_PARAM:
+ platform->Message(HOST_MESSAGE, "Illegal input parameter\n");
+ break;
+ case SD_MMC_ERR_WP:
+ platform->Message(HOST_MESSAGE, "Card write protected\n");
+ break;
+ default:
+ platform->MessageF(HOST_MESSAGE, "Unknown (code %d)\n", err);
+ break;
}
- } while (err != SD_MMC_OK);
+ return;
+ }
// Print some card details (optional)
@@ -89,7 +82,7 @@ void MassStorage::Init()
// Mount the file system
- int mounted = f_mount(0, &fileSystem);
+ FRESULT mounted = f_mount(0, &fileSystem);
if (mounted != FR_OK)
{
platform->MessageF(HOST_MESSAGE, "Can't mount filesystem 0: code %d\n", mounted);
diff --git a/src/Move.cpp b/src/Move.cpp
index a9321da5..b869610e 100644
--- a/src/Move.cpp
+++ b/src/Move.cpp
@@ -64,8 +64,6 @@ void Move::Init()
SetLiveCoordinates(move);
SetPositions(move);
- currentFeedrate = DEFAULT_FEEDRATE/minutesToSeconds;
-
// Set up default bed probe points. This is only a guess, because we don't know the bed size yet.
for (size_t point = 0; point < MAX_PROBE_POINTS; point++)
{
@@ -150,14 +148,10 @@ void Move::Spin()
if (unPreparedTime < 0.5 || unPreparedTime + prevMoveTime < 2.0)
{
// If there's a G Code move available, add it to the DDA ring for processing.
- float nextMove[DRIVES + 1];
- EndstopChecks endStopsToCheck;
- uint8_t moveType;
- FilePosition filePos;
- if (reprap.GetGCodes()->ReadMove(nextMove, endStopsToCheck, moveType, filePos))
+ GCodes::RawMove nextMove;
+ if (reprap.GetGCodes()->ReadMove(nextMove))
{
// We have a new move
- currentFeedrate = nextMove[DRIVES]; // might be G1 with just an F field
#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,
@@ -169,15 +163,14 @@ void Move::Spin()
bool isSegmented;
do
{
- float tempMove[DRIVES + 1];
- memcpy(tempMove, nextMove, sizeof(tempMove));
+ GCodes::RawMove tempMove = nextMove;
isSegmented = SegmentMove(tempMove);
if (isSegmented)
{
// 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[drive] -= tempMove[drive];
+ nextMove.coords[drive] -= tempMove.coords[drive];
}
}
bool doMotorMapping = (moveType == 0) || (moveType == 1 && !IsDeltaMode());
@@ -185,19 +178,19 @@ void Move::Spin()
{
Transform(tempMove);
}
- if (ddaRingAddPointer->Init(tempMove, endStopsToCheck, doMotorMapping, filePos))
+ 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 = (moveType == 0) || (moveType == 1 && !IsDeltaMode());
+ bool doMotorMapping = (nextMove.moveType == 0) || (nextMove.moveType == 1 && !IsDeltaMode());
if (doMotorMapping)
{
- Transform(nextMove);
+ Transform(nextMove.coords);
}
- if (ddaRingAddPointer->Init(nextMove, endStopsToCheck, doMotorMapping, filePos))
+ if (ddaRingAddPointer->Init(nextMove.coords, nextMove.feedRate, nextMove.endStopsToCheck, doMotorMapping, nextMove.filePos))
{
ddaRingAddPointer = ddaRingAddPointer->GetNext();
idleCount = 0;
@@ -287,6 +280,7 @@ void Move::Spin()
// Pause the print as soon as we can.
// Returns the file position of the first queue move we are going to skip, or noFilePosition we we are not skipping any moves.
// We update 'positions' to the positions and feed rate expected for the next move, and the amount of extrusion in the moves we skipped.
+// If we are not skipping any moves then the feed rate is left alone, therefore the caller should set this up first.
FilePosition Move::PausePrint(float positions[DRIVES+1])
{
// Find a move we can pause after.
@@ -370,7 +364,7 @@ FilePosition Move::PausePrint(float positions[DRIVES+1])
}
else
{
- GetCurrentUserPosition(positions, 0); // gets positions and feed rate, and clears out extrusion values
+ GetCurrentUserPosition(positions, 0); // gets positions and clears out extrusion values
}
return fPos;
@@ -421,20 +415,6 @@ void Move::EndPointToMachine(const float coords[], int32_t ep[], size_t numDrive
}
}
-void Move::SetFeedrate(float feedRate)
-{
- if (DDARingEmpty())
- {
- DDA *lastMove = ddaRingAddPointer->GetPrevious();
- currentFeedrate = feedRate;
- lastMove->SetFeedRate(feedRate);
- }
- else
- {
- reprap.GetPlatform()->Message(GENERIC_MESSAGE, "SetFeedrate called when DDA ring not empty\n");
- }
-}
-
// Returns steps from units (mm) for a particular drive
int32_t Move::MotorEndPointToMachine(size_t drive, float coord)
{
@@ -1231,7 +1211,7 @@ void Move::ZProbeTriggered(DDA* hitDDA)
}
// Return the untransformed machine coordinates
-void Move::GetCurrentMachinePosition(float m[DRIVES + 1], bool disableMotorMapping) const
+void Move::GetCurrentMachinePosition(float m[DRIVES], bool disableMotorMapping) const
{
DDA *lastQueuedMove = ddaRingAddPointer->GetPrevious();
for (size_t i = 0; i < DRIVES; i++)
@@ -1245,7 +1225,6 @@ void Move::GetCurrentMachinePosition(float m[DRIVES + 1], bool disableMotorMappi
m[i] = 0.0;
}
}
- m[DRIVES] = currentFeedrate;
}
/*static*/ float Move::MotorEndpointToPosition(int32_t endpoint, size_t drive)
@@ -1262,8 +1241,8 @@ bool Move::IsExtruding() const
return rslt;
}
-// Return the transformed machine coordinates
-void Move::GetCurrentUserPosition(float m[DRIVES + 1], uint8_t moveType) const
+// Return the transformed machine coordinates, leaving the feed rate at m[DRIVES] alone
+void Move::GetCurrentUserPosition(float m[DRIVES], uint8_t moveType) const
{
GetCurrentMachinePosition(m, moveType == 2 || (moveType == 1 && IsDeltaMode()));
if (moveType == 0)
diff --git a/src/Move.h b/src/Move.h
index 2f24b514..0ff228e8 100644
--- a/src/Move.h
+++ b/src/Move.h
@@ -36,7 +36,7 @@ public:
void Init(); // Start me up
void Spin(); // Called in a tight loop to keep the class going
void Exit(); // Shut down
- void GetCurrentUserPosition(float m[DRIVES + 1], uint8_t moveType) const; // Return the position (after all queued moves have been executed) in transformed coords
+ void GetCurrentUserPosition(float m[DRIVES], uint8_t moveType) const; // Return the position (after all queued moves have been executed) in transformed coords
int32_t GetEndPoint(size_t drive) const { return liveEndPoints[drive]; } // Get the current position of a motor
void LiveCoordinates(float m[DRIVES]); // Gives the last point at the end of the last complete DDA transformed to user coords
void Interrupt(); // The hardware's (i.e. platform's) interrupt should call this.
@@ -48,7 +48,6 @@ public:
void HitHighStop(size_t axis, DDA* hitDDA); // What to do when a high endstop is hit
void ZProbeTriggered(DDA* hitDDA); // What to do when a the Z probe is triggered
void SetPositions(const float move[DRIVES]); // Force the coordinates to be these
- void SetFeedrate(float feedRate); // Sometimes we want to override the feed rate
void SetLiveCoordinates(const float coords[DRIVES]); // Force the live coordinates (see above) to be these
void SetXBedProbePoint(size_t index, float x); // Record the X coordinate of a probe point
void SetYBedProbePoint(size_t index, float y); // Record the Y coordinate of a probe point
@@ -111,7 +110,7 @@ private:
void SetProbedBedEquation(size_t numPoints, StringRef& reply); // When we have a full set of probed points, work out the bed's equation
void DoDeltaCalibration(size_t numPoints, StringRef& reply);
void BedTransform(float move[AXES]) const; // Take a position and apply the bed compensations
- void GetCurrentMachinePosition(float m[DRIVES + 1], bool disableMotorMapping) const; // Get the current position and feedrate in untransformed coords
+ void GetCurrentMachinePosition(float m[DRIVES], bool disableMotorMapping) const; // Get the current position in untransformed coords
void InverseBedTransform(float move[AXES]) const; // Go from a bed-transformed point back to user coordinates
void AxisTransform(float move[AXES]) const; // Take a position and apply the axis-angle compensations
void InverseAxisTransform(float move[AXES]) const; // Go from an axis transformed point back to user coordinates
@@ -139,7 +138,6 @@ private:
bool simulating; // Are we simulating, or really printing?
unsigned int idleCount; // The number of times Spin was called and had no new moves to process
float simulationTime; // Print time since we started simulating
- float currentFeedrate; // Err... the current feed rate...
volatile float liveCoordinates[DRIVES]; // The endpoint that the machine moved to in the last completed move
volatile bool liveCoordinatesValid; // True if the XYZ live coordinates are reliable (the extruder ones always are)
volatile int32_t liveEndPoints[DRIVES]; // The XYZ endpoints of the last completed move in motor coordinates
diff --git a/src/Network.cpp b/src/Network.cpp
index edc6563f..81deca97 100644
--- a/src/Network.cpp
+++ b/src/Network.cpp
@@ -97,9 +97,10 @@ static bool closingDataPort = false;
static ConnectionState *sendingConnection = nullptr;
static uint32_t sendingWindow32[(TCP_WND + 3)/4]; // should be 32-bit aligned for efficiency
-static inline char* sendingWindow() { return reinterpret_cast<char*>(sendingWindow32); }
+static char * const sendingWindow = reinterpret_cast<char *>(sendingWindow32);
static uint16_t sendingWindowSize, sentDataOutstanding;
static uint8_t sendingRetries;
+static err_t writeResult, outputResult;
static uint16_t httpPort = DEFAULT_HTTP_PORT;
@@ -153,8 +154,8 @@ static void ethernet_rx_callback(uint32_t ul_status)
}
else
{
- reprap.GetNetwork()->ReadPacket();
ethernet_set_rx_callback(nullptr);
+ reprap.GetNetwork()->ResetCallback();
}
}
@@ -165,15 +166,11 @@ static void conn_err(void *arg, err_t err)
// Report the error to the monitor
reprap.GetPlatform()->MessageF(HOST_MESSAGE, "Network: Connection error, code %d\n", err);
+ // Tell the higher levels about the error
ConnectionState *cs = (ConnectionState*)arg;
if (cs != nullptr)
{
- if (reprap.Debug(moduleNetwork))
- {
- reprap.GetPlatform()->Message(HOST_MESSAGE, "Network: This connection has a valid CS\n");
- }
-
- // Tell the higher levels about the error
+ cs->isTerminated = true;
reprap.GetNetwork()->ConnectionClosed(cs, false);
}
}
@@ -185,37 +182,47 @@ static err_t conn_poll(void *arg, tcp_pcb *pcb)
ConnectionState *cs = (ConnectionState*)arg;
if (cs == sendingConnection)
{
- // Data could not be sent in time, check if the connection has to be timed out
+ // Data could not be sent last time, check if the connection has to be timed out
sendingRetries++;
if (sendingRetries == TCP_MAX_SEND_RETRIES)
{
- reprap.GetPlatform()->MessageF(HOST_MESSAGE, "Network: Poll couldn't send data after %d retries!\n", TCP_MAX_SEND_RETRIES);
+ reprap.GetPlatform()->MessageF(HOST_MESSAGE, "Network: Could not transmit data after %.1f seconds\n", (float)TCP_WRITE_TIMEOUT / 1000.0);
tcp_abort(pcb);
return ERR_ABRT;
}
- // Do we have enough space left for sending? Third-party apps may be sending data as well, so check this first
- if (tcp_sndbuf(pcb) < TCP_WND)
+ // Try to write the remaining data once again (if required)
+ if (writeResult != ERR_OK)
{
- if (reprap.Debug(moduleNetwork))
+ writeResult = tcp_write(pcb, sendingWindow + (sendingWindowSize - sentDataOutstanding), sentDataOutstanding, 0);
+ if (ERR_IS_FATAL(writeResult))
{
- reprap.GetPlatform()->Message(HOST_MESSAGE, "Network: Could not send data because not enough sending space is available\n");
+ reprap.GetPlatform()->MessageF(HOST_MESSAGE, "Network: Failed to write data in conn_poll (code %d)\n", writeResult);
+ tcp_abort(pcb);
+ return ERR_ABRT;
}
- return ERR_MEM;
- }
- // Try to send the remaining data once again
- err_t err = tcp_write(pcb, sendingWindow() + (sendingWindowSize - sentDataOutstanding), sentDataOutstanding, 0);
- if (err == ERR_OK)
- {
- err = tcp_output(pcb);
+ if (writeResult != ERR_OK && reprap.Debug(moduleNetwork))
+ {
+ reprap.GetPlatform()->MessageF(HOST_MESSAGE, "Network: tcp_write resulted in error code %d\n", writeResult);
+ }
}
- if (ERR_IS_FATAL(err))
+ // If that worked, try to output the remaining data (if required)
+ if (outputResult != ERR_OK)
{
- reprap.GetPlatform()->MessageF(HOST_MESSAGE, "Network: Failed to write data in conn_poll (code %d)\n", err);
- tcp_abort(pcb);
- return ERR_ABRT;
+ outputResult = tcp_output(pcb);
+ if (ERR_IS_FATAL(outputResult))
+ {
+ reprap.GetPlatform()->MessageF(HOST_MESSAGE, "Network: Failed to output data in conn_poll (code %d)\n", outputResult);
+ tcp_abort(pcb);
+ return ERR_ABRT;
+ }
+
+ if (outputResult != ERR_OK && reprap.Debug(moduleNetwork))
+ {
+ reprap.GetPlatform()->MessageF(HOST_MESSAGE, "Network: tcp_output resulted in error code %d\n", outputResult);
+ }
}
}
else
@@ -269,7 +276,7 @@ static err_t conn_recv(void *arg, tcp_pcb *pcb, pbuf *p, err_t err)
// Tell higher levels that we are receiving data
processingOk = reprap.GetNetwork()->ReceiveInput(p, cs);
}
- else if (cs->persistConnection)
+ else
{
// Tell higher levels that a connection has been closed
processingOk = reprap.GetNetwork()->ConnectionClosedGracefully(cs);
@@ -277,10 +284,13 @@ static err_t conn_recv(void *arg, tcp_pcb *pcb, pbuf *p, err_t err)
if (!processingOk)
{
+ // Something went wrong, discard whatever has been received
if (p != nullptr)
{
pbuf_free(p);
}
+
+ // Also reset the connection. This will call conn_err() too
tcp_abort(pcb);
return ERR_ABRT;
}
@@ -360,7 +370,7 @@ void telnetd_init()
Network::Network(Platform* p)
: platform(p), freeTransactions(nullptr), readyTransactions(nullptr), writingTransactions(nullptr),
- state(NetworkInactive), isEnabled(true), readingData(false),
+ state(NetworkInactive), isEnabled(true), resetCallback(false),
dataCs(nullptr), ftpCs(nullptr), telnetCs(nullptr), freeConnections(nullptr)
{
for (size_t i = 0; i < NETWORK_TRANSACTION_COUNT; i++)
@@ -378,22 +388,6 @@ Network::Network(Platform* p)
strcpy(hostname, HOSTNAME);
}
-void Network::AppendTransaction(NetworkTransaction* volatile* list, NetworkTransaction *r)
-{
- r->next = nullptr;
- while (*list != nullptr)
- {
- list = &((*list)->next);
- }
- *list = r;
-}
-
-void Network::PrependTransaction(NetworkTransaction* volatile* list, NetworkTransaction *r)
-{
- r->next = *list;
- *list = r;
-}
-
void Network::Init()
{
longWait = platform->Time();
@@ -413,47 +407,38 @@ void Network::Spin()
if (state == NetworkActive && hasLink)
{
// See if we can read any packets
-
- if (readingData)
+ ethernet_task();
+ if (resetCallback)
{
- ethernet_task();
- readingData = false;
+ resetCallback = false;
ethernet_set_rx_callback(&ethernet_rx_callback);
}
// See if we can send anything
-
- NetworkTransaction *r = writingTransactions;
- if (r != nullptr && sendingConnection == nullptr)
+ NetworkTransaction *transaction = writingTransactions;
+ if (transaction != nullptr && sendingConnection == nullptr)
{
- if (r->next != nullptr)
+ if (transaction->next != nullptr)
{
- // Data is supposed to be sent to another connection and the last packet has
- // been acknowledged. Rotate the sending transactions so every client is
- // served even while big files are being sent.
- NetworkTransaction *rn = r->next;
- writingTransactions = rn;
- AppendTransaction(&writingTransactions, r);
- r = rn;
+ // Data is supposed to be sent and the last packet has been acknowledged.
+ // Rotate the transactions so every client is served even while multiple files are sent
+ NetworkTransaction *next = transaction->next;
+ writingTransactions = next;
+ AppendTransaction(&writingTransactions, transaction);
+ transaction = next;
}
- if (r->Send())
+ if (transaction->Send())
{
- // We're done, free up this transaction
- ConnectionState *cs = r->cs;
- NetworkTransaction *rn = r->nextWrite;
- writingTransactions = r->next;
- AppendTransaction(&freeTransactions, r);
+ // This transaction can be released, do this here
+ writingTransactions = transaction->next;
+ PrependTransaction(&freeTransactions, transaction);
- // If there is more data to write on this connection, do it next time
-
- if (cs != nullptr)
- {
- cs->sendingTransaction = rn;
- }
- if (rn != nullptr)
+ // If there is more data to write on this connection, do it sometime soon
+ NetworkTransaction *nextWrite = transaction->nextWrite;
+ if (nextWrite != nullptr)
{
- PrependTransaction(&writingTransactions, rn);
+ PrependTransaction(&writingTransactions, nextWrite);
}
}
}
@@ -518,72 +503,31 @@ void Network::Diagnostics()
#endif
}
-void Network::Enable()
+void Network::ResetCallback()
{
- if (state == NetworkPreInitializing)
- {
- // We must call this one only once, otherwise we risk a firmware crash
- init_ethernet(platform->MACAddress(), hostname);
- state = NetworkPostInitializing;
- }
-
- if (!isEnabled)
- {
- readingData = true;
- isEnabled = true;
- // EMAC RX callback will be reset on next Spin calls
- if (state == NetworkInactive)
- {
- state = NetworkActive;
- }
- }
+ resetCallback = true;
}
-void Network::Disable()
+// Called when data has been received. Return false if we cannot process it
+bool Network::ReceiveInput(pbuf *pb, ConnectionState* cs)
{
- if (isEnabled)
+ NetworkTransaction* r = freeTransactions;
+ if (r == nullptr)
{
- readingData = false;
- ethernet_set_rx_callback(nullptr);
- if (state == NetworkActive)
- {
- state = NetworkInactive;
- }
- isEnabled = false;
+ platform->Message(HOST_MESSAGE, "Network::ReceiveInput() - no free transactions!\n");
+ return false;
}
-}
-
-bool Network::IsEnabled() const
-{
- return isEnabled;
-}
-
-uint16_t Network::GetHttpPort() const
-{
- return httpPort;
-}
-void Network::SetHttpPort(uint16_t port)
-{
- if (state == NetworkActive && port != httpPort)
- {
- // Close old HTTP port
- tcp_close(http_pcb);
-
- // Create a new one for the new port
- tcp_pcb* pcb = tcp_new();
- tcp_bind(pcb, IP_ADDR_ANY, port);
- http_pcb = tcp_listen(pcb);
- tcp_accept(http_pcb, conn_accept);
+ freeTransactions = r->next;
+ r->Set(pb, cs, receiving);
- // Update mDNS services
- mdns_services[MDNS_HTTP_SERVICE_INDEX].port = port;
- mdns_announce();
- }
- httpPort = port;
+ AppendTransaction(&readyTransactions, r);
+// debugPrintf("Network - input received\n");
+ return true;
}
-// This is called when a connection is being established and returns an initialised ConnectionState instance.
+// This is called when a connection is being established and returns an initialised ConnectionState instance
+// or NULL if no more items are available. This would reset the connection immediately
ConnectionState *Network::ConnectionAccepted(tcp_pcb *pcb)
{
ConnectionState *cs = freeConnections;
@@ -593,19 +537,21 @@ ConnectionState *Network::ConnectionAccepted(tcp_pcb *pcb)
return nullptr;
}
- NetworkTransaction* r = freeTransactions;
- if (r == nullptr)
+ NetworkTransaction* transaction = freeTransactions;
+ if (transaction == nullptr)
{
platform->Message(HOST_MESSAGE, "Network::ConnectionAccepted() - no free transactions!\n");
return nullptr;
}
+ // Initialise a new connection
freeConnections = cs->next;
cs->Init(pcb);
- r->Set(nullptr, cs, connected);
- freeTransactions = r->next;
- AppendTransaction(&readyTransactions, r);
+ // Notify the webserver about this
+ transaction->Set(nullptr, cs, connected);
+ freeTransactions = transaction->next;
+ AppendTransaction(&readyTransactions, transaction);
return cs;
}
@@ -616,10 +562,20 @@ void Network::ConnectionClosed(ConnectionState* cs, bool closeConnection)
// Make sure these connections are not reused. Remove all references to it
if (cs == dataCs)
{
+ // FTP data connection
dataCs = nullptr;
+
+ if (closingDataPort && ftp_pasv_pcb != nullptr)
+ {
+ tcp_accept(ftp_pasv_pcb, nullptr);
+ tcp_close(ftp_pasv_pcb);
+ ftp_pasv_pcb = nullptr;
+ }
+ closingDataPort = false;
}
if (cs == ftpCs)
{
+ // Main FTP connection
ftpCs = nullptr;
}
if (cs == telnetCs)
@@ -628,17 +584,17 @@ void Network::ConnectionClosed(ConnectionState* cs, bool closeConnection)
}
if (cs == sendingConnection)
{
+ // Stop sending if the connection is going down
sendingConnection = nullptr;
}
- // Close it if requested
+ // Remove all callbacks and close the PCB if requested
tcp_pcb *pcb = cs->pcb;
+ tcp_sent(pcb, nullptr);
+ tcp_recv(pcb, nullptr);
+ tcp_poll(pcb, nullptr, TCP_WRITE_TIMEOUT / TCP_SLOW_INTERVAL / TCP_MAX_SEND_RETRIES);
if (pcb != nullptr && closeConnection)
{
- tcp_arg(pcb, nullptr);
- tcp_sent(pcb, nullptr);
- tcp_recv(pcb, nullptr);
- tcp_poll(pcb, nullptr, TCP_WRITE_TIMEOUT / TCP_SLOW_INTERVAL / TCP_MAX_SEND_RETRIES);
tcp_close(pcb);
}
cs->pcb = nullptr;
@@ -646,40 +602,95 @@ void Network::ConnectionClosed(ConnectionState* cs, bool closeConnection)
// Inform the Webserver that we are about to remove an existing connection
reprap.GetWebserver()->ConnectionLost(cs);
- // cs points to a connection state block that the caller is about to release, so we need to stop referring to it.
- // There may be one NetworkTransaction in the writing or closing list referring to it, and possibly more than one in the ready list.
-
- for (NetworkTransaction* r = readyTransactions; r != nullptr; r = r->next)
+ // Remove all transactions that point to cs from the list of ready transactions
+ NetworkTransaction *previous = nullptr, *item = readyTransactions;
+ while (item != nullptr)
{
- if (r->cs == cs)
+ if (item->cs == cs)
{
- r->SetConnectionLost();
+ item->Discard();
+ item = (previous == nullptr) ? readyTransactions : previous->next;
+ }
+ else
+ {
+ previous = item;
+ item = item->next;
}
}
- if (cs->sendingTransaction != nullptr)
+ // Do the same for the writing transaction. There is only one transaction on writingTransactions
+ // per connection and cs->sendingTransaction points to it. Check if we have to free it here
+ NetworkTransaction *sendingTransaction = cs->sendingTransaction;
+ if (sendingTransaction != nullptr)
{
- cs->sendingTransaction->SetConnectionLost();
- cs->sendingTransaction = nullptr;
+ // Take care of other transactions that want to write data over the closed connection too
+ NetworkTransaction *nextWrite = sendingTransaction->nextWrite;
+ while (nextWrite != nullptr)
+ {
+ NetworkTransaction *temp = nextWrite;
+ nextWrite = nextWrite->nextWrite;
+ temp->Discard();
+ }
+
+ // Unlink the sending transaction from the writing transactions
+ previous = nullptr;
+ for(item = writingTransactions; item != nullptr; item = item->next)
+ {
+ if (item == sendingTransaction)
+ {
+ if (previous == nullptr)
+ {
+ writingTransactions = item->next;
+ }
+ else
+ {
+ previous->next = item->next;
+ }
+ break;
+ }
+ previous = item;
+ }
+
+ // Discard it. This will add it back to the list of free transactions too
+ sendingTransaction->Discard();
}
+ // Free up this cs again
cs->next = freeConnections;
freeConnections = cs;
}
-// This enqueues a new transaction to indicate a graceful reset. Do this to keep the time line of incoming transactions valid
+// This enqueues a new transaction to indicate a graceful reset. Do this to keep the time line of incoming transactions valid.
+// Return false if we cannot process this event, which would result in an immediate connection reset
bool Network::ConnectionClosedGracefully(ConnectionState *cs)
{
- NetworkTransaction* r = freeTransactions;
- if (r == nullptr)
+ // We need a valid transaction to do something.
+ // If that fails, the connection will be reset and the error handler will take care of this connection
+ NetworkTransaction *transaction = freeTransactions;
+ if (transaction == nullptr)
{
platform->Message(HOST_MESSAGE, "Network::ConnectionClosedGracefully() - no free transactions!\n");
return false;
}
- freeTransactions = r->next;
- r->Set(nullptr, cs, disconnected);
- AppendTransaction(&readyTransactions, r);
+ // Invalidate the PCB
+ tcp_sent(cs->pcb, nullptr);
+ tcp_recv(cs->pcb, nullptr);
+ tcp_poll(cs->pcb, nullptr, TCP_WRITE_TIMEOUT / TCP_SLOW_INTERVAL / TCP_MAX_SEND_RETRIES);
+ tcp_close(cs->pcb);
+ cs->pcb = nullptr;
+
+ // Close the sending transaction (if any)
+ NetworkTransaction *sendingTransaction = cs->sendingTransaction;
+ if (sendingTransaction != nullptr)
+ {
+ sendingTransaction->Close();
+ }
+
+ // Notify the webserver about this event
+ freeTransactions = transaction->next;
+ transaction->Set(nullptr, cs, disconnected);
+ AppendTransaction(&readyTransactions, transaction);
return true;
}
@@ -698,26 +709,96 @@ bool Network::InLwip() const
return lwipLocked;
}
-void Network::ReadPacket()
+const uint8_t *Network::IPAddress() const
{
- readingData = true;
+ return ethernet_get_ipaddress();
}
-bool Network::ReceiveInput(pbuf *pb, ConnectionState* cs)
+void Network::SetIPAddress(const uint8_t ipAddress[], const uint8_t netmask[], const uint8_t gateway[])
{
- NetworkTransaction* r = freeTransactions;
- if (r == nullptr)
+ if (state == NetworkActive)
{
- platform->Message(HOST_MESSAGE, "Network::ReceiveInput() - no free transactions!\n");
- return false;
+ // This performs IP changes on-the-fly
+ ethernet_set_configuration(ipAddress, netmask, gateway);
+
+ // Announce mDNS services again
+ mdns_announce();
}
+}
- freeTransactions = r->next;
- r->Set(pb, cs, dataReceiving);
+// Set the network hostname. Removes all whitespaces and converts the name to lower-case.
+void Network::SetHostname(const char *name)
+{
+ size_t i = 0;
+ while (*name && i < ARRAY_UPB(hostname))
+ {
+ char c = *name++;
+ if (c >= 'A' && c <= 'Z')
+ {
+ c += 'a' - 'A';
+ }
- AppendTransaction(&readyTransactions, r);
-// debugPrintf("Network - input received\n");
- return true;
+ if ((c >= 'a' && c <= 'z') || (c >= '0' && c <= '9') || (c == '-') || (c == '_'))
+ {
+ hostname[i++] = c;
+ }
+ }
+
+ if (i > 0)
+ {
+ hostname[i] = 0;
+ }
+ else
+ {
+ // Don't allow empty hostnames
+ strcpy(hostname, HOSTNAME);
+ }
+
+ if (state == NetworkActive)
+ {
+ mdns_update_hostname();
+ }
+}
+
+void Network::Enable()
+{
+ if (state == NetworkPreInitializing)
+ {
+ // We must call this one only once, otherwise we risk a firmware crash
+ init_ethernet(platform->MACAddress(), hostname);
+ state = NetworkPostInitializing;
+ }
+
+ if (!isEnabled)
+ {
+ resetCallback = true;
+ isEnabled = true;
+ // EMAC RX callback will be reset on next Spin calls
+
+ if (state == NetworkInactive)
+ {
+ state = NetworkActive;
+ }
+ }
+}
+
+void Network::Disable()
+{
+ if (isEnabled)
+ {
+ resetCallback = false;
+ ethernet_set_rx_callback(nullptr);
+ if (state == NetworkActive)
+ {
+ state = NetworkInactive;
+ }
+ isEnabled = false;
+ }
+}
+
+bool Network::IsEnabled() const
+{
+ return isEnabled;
}
// This is called by the web server to get a new received packet.
@@ -734,25 +815,6 @@ NetworkTransaction *Network::GetTransaction(const ConnectionState *cs)
return nullptr;
}
- // If we're waiting for a new connection on a data port, see if there is a matching transaction available
- if (cs == nullptr && rs->waitingForDataConnection)
- {
- for (NetworkTransaction *rsNext = rs->next; rsNext != nullptr; rsNext = rs->next)
- {
- if (rsNext->status == connected && rsNext->GetLocalPort() > 1023)
- {
- rs->next = rsNext->next; // remove rsNext from the list
- rsNext->next = readyTransactions;
- readyTransactions = rsNext;
- return rsNext;
- }
-
- rs = rsNext;
- }
-
- return readyTransactions; // nothing found, process this transaction once again
- }
-
// See if the first one is the transaction we're looking for
if (cs == nullptr || rs->cs == cs)
{
@@ -776,32 +838,20 @@ NetworkTransaction *Network::GetTransaction(const ConnectionState *cs)
return nullptr;
}
-
-
-// The current NetworkTransaction must be processed again,
-// e.g. because we're still waiting for another data connection.
-void Network::WaitForDataConection()
-{
- NetworkTransaction *r = readyTransactions;
- r->waitingForDataConnection = true;
- r->inputPointer = 0; // behave as if this request hasn't been processed yet
-}
-
-const uint8_t *Network::IPAddress() const
+void Network::AppendTransaction(NetworkTransaction* volatile* list, NetworkTransaction *r)
{
- return ethernet_get_ipaddress();
+ r->next = nullptr;
+ while (*list != nullptr)
+ {
+ list = &((*list)->next);
+ }
+ *list = r;
}
-void Network::SetIPAddress(const uint8_t ipAddress[], const uint8_t netmask[], const uint8_t gateway[])
+void Network::PrependTransaction(NetworkTransaction* volatile* list, NetworkTransaction *r)
{
- if (state == NetworkActive)
- {
- // This performs IP changes on-the-fly
- ethernet_set_configuration(ipAddress, netmask, gateway);
-
- // Announce mDNS services again
- mdns_announce();
- }
+ r->next = *list;
+ *list = r;
}
void Network::OpenDataPort(uint16_t port)
@@ -818,6 +868,31 @@ uint16_t Network::GetDataPort() const
return (closingDataPort || (ftp_pasv_pcb == nullptr) ? 0 : ftp_pasv_pcb->local_port);
}
+uint16_t Network::GetHttpPort() const
+{
+ return httpPort;
+}
+
+void Network::SetHttpPort(uint16_t port)
+{
+ if (state == NetworkActive && port != httpPort)
+ {
+ // Close old HTTP port
+ tcp_close(http_pcb);
+
+ // Create a new one for the new port
+ tcp_pcb* pcb = tcp_new();
+ tcp_bind(pcb, IP_ADDR_ANY, port);
+ http_pcb = tcp_listen(pcb);
+ tcp_accept(http_pcb, conn_accept);
+
+ // Update mDNS services
+ mdns_services[MDNS_HTTP_SERVICE_INDEX].port = port;
+ mdns_announce();
+ }
+ httpPort = port;
+}
+
// Close FTP data port and purge associated PCB
void Network::CloseDataPort()
{
@@ -828,8 +903,8 @@ void Network::CloseDataPort()
}
closingDataPort = true;
- // Close remote connection of our data port or do it as soon as the current transaction has finished
- if (dataCs != nullptr && dataCs->pcb != nullptr)
+ // Close remote connection of our data port or do it as soon as the last packet has been sent
+ if (dataCs != nullptr)
{
NetworkTransaction *mySendingTransaction = dataCs->sendingTransaction;
if (mySendingTransaction != nullptr)
@@ -865,12 +940,6 @@ void Network::SaveTelnetConnection()
telnetCs = readyTransactions->cs;
}
-// Check if there are enough resources left to allocate another NetworkTransaction for sending
-bool Network::CanAcquireTransaction()
-{
- return (freeTransactions != nullptr);
-}
-
bool Network::AcquireFTPTransaction()
{
return AcquireTransaction(ftpCs);
@@ -904,20 +973,22 @@ bool Network::AcquireTransaction(ConnectionState *cs)
}
// See if we're already writing on this connection
- NetworkTransaction *firstTransaction = cs->sendingTransaction;
- NetworkTransaction *lastTransaction = firstTransaction;
+ NetworkTransaction *previousTransaction = cs->sendingTransaction;
+ NetworkTransaction *lastTransaction = previousTransaction;
if (lastTransaction != nullptr)
{
while (lastTransaction->nextWrite != nullptr)
{
+ previousTransaction = lastTransaction;
lastTransaction = lastTransaction->nextWrite;
}
}
// Then check if this transaction is valid and safe to use
NetworkTransaction *transactionToUse;
- if (firstTransaction != nullptr && firstTransaction != lastTransaction && lastTransaction->fileBeingSent == nullptr)
+ if (previousTransaction != lastTransaction && lastTransaction->fileBeingSent == nullptr)
{
+ previousTransaction->nextWrite = nullptr;
transactionToUse = lastTransaction;
}
// We cannot use it, so try to allocate a free one
@@ -930,7 +1001,7 @@ bool Network::AcquireTransaction(ConnectionState *cs)
return false;
}
freeTransactions = transactionToUse->next;
- transactionToUse->Set(nullptr, cs, dataReceiving); // set it to dataReceiving as we expect a response
+ transactionToUse->Set(nullptr, cs, acquired);
}
// Replace the first entry of readyTransactions with our new transaction, so it can be used by Commit().
@@ -938,40 +1009,6 @@ bool Network::AcquireTransaction(ConnectionState *cs)
return true;
}
-// Set the DHCP hostname. Removes all whitespaces and converts the name to lower-case.
-void Network::SetHostname(const char *name)
-{
- size_t i = 0;
- while (*name && i < ARRAY_UPB(hostname))
- {
- char c = *name++;
- if (c >= 'A' && c <= 'Z')
- {
- c += 'a' - 'A';
- }
-
- if ((c >= 'a' && c <= 'z') || (c >= '0' && c <= '9') || (c == '-') || (c == '_'))
- {
- hostname[i++] = c;
- }
- }
-
- if (i != 0)
- {
- hostname[i] = 0;
- }
- else
- {
- // Don't allow empty hostnames
- strcpy(hostname, HOSTNAME);
- }
-
- if (state == NetworkActive)
- {
- mdns_update_hostname();
- }
-}
-
//***************************************************************************************************
// ConnectionState class
@@ -985,12 +1022,21 @@ void ConnectionState::Init(tcp_pcb *p)
next = nullptr;
sendingTransaction = nullptr;
persistConnection = true;
+ isTerminated = false;
+}
+
+void ConnectionState::Terminate()
+{
+ if (pcb != nullptr)
+ {
+ tcp_abort(pcb);
+ }
}
//***************************************************************************************************
// NetworkTransaction class
-NetworkTransaction::NetworkTransaction(NetworkTransaction *n) : next(n)
+NetworkTransaction::NetworkTransaction(NetworkTransaction *n) : next(n), status(released)
{
sendStack = new OutputStack();
}
@@ -999,20 +1045,19 @@ void NetworkTransaction::Set(pbuf *p, ConnectionState *c, TransactionStatus s)
{
cs = c;
pb = readingPb = p;
- bufferLength = (p == nullptr) ? 0 : pb->tot_len;
status = s;
inputPointer = 0;
sendBuffer = nullptr;
fileBeingSent = nullptr;
closeRequested = false;
nextWrite = nullptr;
- waitingForDataConnection = false;
+ dataAcknowledged = false;
}
// Read one char from the NetworkTransaction
bool NetworkTransaction::Read(char& b)
{
- if (LostConnection() || readingPb == nullptr)
+ if (readingPb == nullptr)
{
b = 0;
return false;
@@ -1028,9 +1073,9 @@ bool NetworkTransaction::Read(char& b)
}
// Read data from the NetworkTransaction and return true on success
-bool NetworkTransaction::ReadBuffer(const char *&buffer, unsigned int &len)
+bool NetworkTransaction::ReadBuffer(const char *&buffer, size_t &len)
{
- if (LostConnection() || readingPb == nullptr)
+ if (readingPb == nullptr)
{
return false;
}
@@ -1126,7 +1171,6 @@ void NetworkTransaction::Write(OutputStack *stack)
}
}
-// Write formatted data to the output buffer
void NetworkTransaction::Printf(const char* fmt, ...)
{
if (CanWrite() && (sendBuffer != nullptr || OutputBuffer::Allocate(sendBuffer)))
@@ -1150,48 +1194,13 @@ void NetworkTransaction::SetFileToWrite(FileStore *file)
}
}
-// Send exactly one TCP window of data and return true when done
+// Send exactly one TCP window of data and return true when this transaction can be released
bool NetworkTransaction::Send()
{
- // Free up this transaction if we either lost the connection or if it is supposed to be closed
- if (LostConnection() || closeRequested)
- {
- if (fileBeingSent != nullptr)
- {
- fileBeingSent->Close();
- fileBeingSent = nullptr;
- }
-
- OutputBuffer::ReleaseAll(sendBuffer);
- sendStack->ReleaseAll();
-
- if (!LostConnection())
- {
- reprap.GetNetwork()->ConnectionClosed(cs, true);
- }
-
- if (closingDataPort)
- {
- if (ftp_pasv_pcb != nullptr)
- {
- tcp_accept(ftp_pasv_pcb, nullptr);
- tcp_close(ftp_pasv_pcb);
- ftp_pasv_pcb = nullptr;
- }
-
- closingDataPort = false;
- }
-
- return true;
- }
-
- // Do we have enough space left for sending? Third-party apps may be sending data as well, so check this first
- if (tcp_sndbuf(cs->pcb) < TCP_WND)
+ // Free up this transaction if the connection is supposed to be closed
+ if (closeRequested)
{
- if (reprap.Debug(moduleNetwork))
- {
- reprap.GetPlatform()->Message(HOST_MESSAGE, "Network: Could not send data because not enough sending space is available\n");
- }
+ reprap.GetNetwork()->ConnectionClosed(cs, true); // This will release the transaction too
return false;
}
@@ -1200,7 +1209,7 @@ bool NetworkTransaction::Send()
while (sendBuffer != nullptr && bytesLeftToSend > 0)
{
size_t copyLength = min<size_t>(bytesLeftToSend, sendBuffer->BytesLeft());
- memcpy(sendingWindow() + bytesBeingSent, sendBuffer->Read(copyLength), copyLength);
+ memcpy(sendingWindow + bytesBeingSent, sendBuffer->Read(copyLength), copyLength);
bytesBeingSent += copyLength;
bytesLeftToSend -= copyLength;
@@ -1222,7 +1231,7 @@ bool NetworkTransaction::Send()
size_t bytesToRead = bytesLeftToSend & (~3);
if (bytesToRead != 0)
{
- int bytesRead = fileBeingSent->Read(sendingWindow() + bytesBeingSent, bytesToRead);
+ int bytesRead = fileBeingSent->Read(sendingWindow + bytesBeingSent, bytesToRead);
if (bytesRead > 0)
{
bytesBeingSent += bytesRead;
@@ -1238,111 +1247,202 @@ bool NetworkTransaction::Send()
if (bytesBeingSent == 0)
{
- // If we have no data to send and fileBeingSent is nullptr, we can close the connection next time
+ // If we have no data to send, this connection can be closed next time
if (!cs->persistConnection && nextWrite == nullptr)
{
Close();
return false;
}
- // We want to send data from another transaction, so only free up this one
+ // We want to send data from another transaction as well, so only free up this one
+ cs->sendingTransaction = nextWrite;
return true;
}
// The TCP window has been filled up as much as possible, so send it now. There is no need to check
// the available space in the SNDBUF queue, because we really write only one TCP window at once.
- err_t result = tcp_write(cs->pcb, sendingWindow(), bytesBeingSent, 0);
- if (result == ERR_OK)
+ writeResult = tcp_write(cs->pcb, sendingWindow, bytesBeingSent, 0);
+ if (ERR_IS_FATAL(writeResult))
{
- result = tcp_output(cs->pcb);
+ reprap.GetPlatform()->MessageF(HOST_MESSAGE, "Network: Failed to write data in Send (code %d)\n", writeResult);
+ tcp_abort(cs->pcb);
+ return false;
}
- if (ERR_IS_FATAL(result))
+ outputResult = tcp_output(cs->pcb);
+ if (ERR_IS_FATAL(outputResult))
{
- reprap.GetPlatform()->MessageF(HOST_MESSAGE, "Network: Failed to write data in Send (code %d)\n", result);
+ reprap.GetPlatform()->MessageF(HOST_MESSAGE, "Network: Failed to output data in Send (code %d)\n", outputResult);
tcp_abort(cs->pcb);
- cs->pcb = nullptr;
return false;
}
+ if (outputResult != ERR_OK && reprap.Debug(moduleNetwork))
+ {
+ reprap.GetPlatform()->MessageF(HOST_MESSAGE, "Network: tcp_output resulted in error code %d\n", outputResult);
+ }
+ // Set LwIP callbacks for ACK and retransmission handling
tcp_poll(cs->pcb, conn_poll, TCP_WRITE_TIMEOUT / TCP_SLOW_INTERVAL / TCP_MAX_SEND_RETRIES);
tcp_sent(cs->pcb, conn_sent);
+ // Set all values for the send process
sendingConnection = cs;
sendingRetries = 0;
sendingWindowSize = sentDataOutstanding = bytesBeingSent;
return false;
}
-// This is called by the Webserer to send output data to a client. If keepConnectionAlive is set to false,
-// the current connection is terminated once everything has been sent.
+// This is called by the Webserver to send output data to a client. If keepConnectionAlive is set to false,
+// the current connection will be terminated once everything has been sent.
void NetworkTransaction::Commit(bool keepConnectionAlive)
{
- if (status == dataSending)
+ // If the connection has been terminated (e.g. RST received while writing upload data), discard this transaction
+ if (!IsConnected() || status == released)
{
- reprap.GetNetwork()->readyTransactions = next;
- // This transaction is already on the list of sending transactions. Pretend it's already complete
+ Discard();
+ return;
}
- else
+
+ // Free buffer holding the incoming data and prepare some values for the sending process
+ FreePbuf();
+ cs->persistConnection = keepConnectionAlive;
+ if (sendBuffer == nullptr)
{
- if (LostConnection())
- {
- // Discard transaction if no connection is available
- Discard();
- }
- else
+ sendBuffer = sendStack->Pop();
+ }
+ status = sending;
+
+ // Unlink the item(s) from the list of ready transactions
+ if (keepConnectionAlive)
+ {
+ // Our connection is still of interest, remove only this transaction from the list
+ NetworkTransaction *previous = nullptr;
+ for(NetworkTransaction *item = reprap.GetNetwork()->readyTransactions; item != nullptr; item = item->next)
{
- // We intend to send data, so move this transaction and prepare some values
- FreePbuf();
- reprap.GetNetwork()->readyTransactions = next;
- cs->persistConnection = keepConnectionAlive;
- if (sendBuffer == nullptr)
+ if (item == this)
{
- sendBuffer = sendStack->Pop();
+ if (previous == nullptr)
+ {
+ reprap.GetNetwork()->readyTransactions = next;
+ }
+ else
+ {
+ previous->next = next;
+ }
+ break;
}
- status = dataSending;
+ previous = item;
+ }
+ }
+ else
+ {
+ // We will close this connection soon, stop receiving data from this PCB
+ tcp_recv(cs->pcb, nullptr);
- // Enqueue this transaction, so it's sent in the right order
- NetworkTransaction *mySendingTransaction = cs->sendingTransaction;
- if (mySendingTransaction == nullptr)
+ // Also remove all ready transactions pointing to our ConnectionState
+ NetworkTransaction *previous = nullptr, *item = reprap.GetNetwork()->readyTransactions;
+ while (item != nullptr)
+ {
+ if (item->cs == cs)
{
- cs->sendingTransaction = this;
- NetworkTransaction * volatile * writingTransactions = &reprap.GetNetwork()->writingTransactions;
- reprap.GetNetwork()->AppendTransaction(writingTransactions, this);
+ if (item == this)
+ {
+ // Only unlink this item
+ if (previous == nullptr)
+ {
+ reprap.GetNetwork()->readyTransactions = next;
+ }
+ else
+ {
+ previous->next = next;
+ }
+ item = next;
+ }
+ else
+ {
+ // Remove all others
+ item->Discard();
+ item = (previous == nullptr) ? reprap.GetNetwork()->readyTransactions : previous->next;
+ }
}
else
{
- while (mySendingTransaction->nextWrite != nullptr)
- {
- mySendingTransaction = mySendingTransaction->nextWrite;
- }
- mySendingTransaction->nextWrite = this;
+ previous = item;
+ item = item->next;
}
}
}
+
+ // Enqueue this transaction, so it's sent in the right order
+ NetworkTransaction *mySendingTransaction = cs->sendingTransaction;
+ if (mySendingTransaction == nullptr)
+ {
+ cs->sendingTransaction = this;
+ reprap.GetNetwork()->AppendTransaction(&reprap.GetNetwork()->writingTransactions, this);
+ }
+ else
+ {
+ while (mySendingTransaction->nextWrite != nullptr)
+ {
+ mySendingTransaction = mySendingTransaction->nextWrite;
+ }
+ mySendingTransaction->nextWrite = this;
+ }
}
-void NetworkTransaction::Defer()
+// Call this to perform some networking tasks while processing deferred requests.
+// If keepData is true, then the pbuf won't be released so it can be reused
+void NetworkTransaction::Defer(bool keepData)
{
- // First free up the allocated pbufs
- FreePbuf();
+ // See if we have to keep the data for future calls
+ if (keepData)
+ {
+ inputPointer = 0;
+ readingPb = pb;
+ if (IsConnected() && pb != nullptr && !dataAcknowledged)
+ {
+ tcp_recved(cs->pcb, pb->tot_len);
+ dataAcknowledged = true;
+ }
+ }
+ else
+ {
+ FreePbuf(); // Free up the allocated pbufs
+ }
+ status = deferred;
- // Call LWIP task to process tcp_recved(). This will hopefully send an ACK
- ethernet_task();
+ // Unlink this transaction from the list of ready transactions and append it again
+ NetworkTransaction *previous = nullptr;
+ for(NetworkTransaction *item = reprap.GetNetwork()->readyTransactions; item != nullptr; item = item->next)
+ {
+ if (item == this)
+ {
+ if (previous == nullptr)
+ {
+ reprap.GetNetwork()->readyTransactions = next;
+ }
+ else
+ {
+ previous->next = next;
+ }
+ break;
+ }
+ previous = item;
+ }
+ reprap.GetNetwork()->AppendTransaction(&reprap.GetNetwork()->readyTransactions, this);
}
-// This method should be called if we don't want to send data to the client and if
-// we don't want to interfere with the connection state, i.e. keep it alive.
+// This method should be called if we don't want to send data to the client and if we
+// don't want to interfere with the connection state. May also be called from ISR!
void NetworkTransaction::Discard()
{
- // Is this the transaction we should be dealing with?
- if (reprap.GetNetwork()->readyTransactions != this)
+ // Can we do anything?
+ if (status == released)
{
- // Should never get here
+ // No - don't free up released items multiple times
return;
}
- reprap.GetNetwork()->readyTransactions = next;
// Free up some resources
FreePbuf();
@@ -1356,47 +1456,54 @@ void NetworkTransaction::Discard()
OutputBuffer::ReleaseAll(sendBuffer);
sendStack->ReleaseAll();
- // Release this transaction unless it's still in use for sending
- if (status != dataSending)
+ // Unlink this transactions from the list of ready transactions and free it. It is then appended to the list of
+ // free transactions because we don't want to risk reusing it when the ethernet ISR processes incoming data
+ NetworkTransaction *previous = nullptr;
+ for(NetworkTransaction *item = reprap.GetNetwork()->readyTransactions; item != nullptr; item = item->next)
{
- NetworkTransaction * volatile * freeTransactions = &reprap.GetNetwork()->freeTransactions;
- reprap.GetNetwork()->AppendTransaction(freeTransactions, this);
+ if (item == this)
+ {
+ if (previous == nullptr)
+ {
+ reprap.GetNetwork()->readyTransactions = next;
+ }
+ else
+ {
+ previous->next = next;
+ }
+ break;
+ }
+ previous = item;
}
+ reprap.GetNetwork()->AppendTransaction(&reprap.GetNetwork()->freeTransactions, this);
+ bool callDisconnectHandler = (cs != nullptr && status == disconnected);
+ status = released;
- // Call disconnect event if this transaction indicates a graceful disconnect
- if (!LostConnection() && status == disconnected)
+ // Call disconnect event if this transaction indicates a graceful disconnect and if the connection
+ // still persists (may not be the case if a RST packet was received before)
+ if (callDisconnectHandler)
{
if (reprap.Debug(moduleNetwork))
{
reprap.GetPlatform()->MessageF(HOST_MESSAGE, "Network: Discard() is handling a graceful disconnect for cs=%08x\n", (unsigned int)cs);
}
- reprap.GetNetwork()->ConnectionClosed(cs, true);
- }
-}
-
-void NetworkTransaction::SetConnectionLost()
-{
- cs = nullptr;
- FreePbuf();
- for (NetworkTransaction *rs = nextWrite; rs != nullptr; rs = rs->nextWrite)
- {
- rs->cs = nullptr;
+ reprap.GetNetwork()->ConnectionClosed(cs, false);
}
}
uint32_t NetworkTransaction::GetRemoteIP() const
{
- return (cs != nullptr) ? cs->pcb->remote_ip.addr : 0;
+ return (cs != nullptr) ? cs->GetRemoteIP() : 0;
}
uint16_t NetworkTransaction::GetRemotePort() const
{
- return (cs != nullptr) ? cs->pcb->remote_port : 0;
+ return (cs != nullptr) ? cs->GetRemotePort() : 0;
}
uint16_t NetworkTransaction::GetLocalPort() const
{
- return (cs != nullptr) ? cs->pcb->local_port : 0;
+ return (cs != nullptr) ? cs->GetLocalPort() : 0;
}
void NetworkTransaction::Close()
@@ -1408,14 +1515,14 @@ void NetworkTransaction::Close()
void NetworkTransaction::FreePbuf()
{
- // Tell LWIP that we have processed data
- if (cs != nullptr && bufferLength > 0 && cs->pcb != nullptr)
+ // See if we have to send an ACK to the client
+ if (IsConnected() && pb != nullptr && !dataAcknowledged)
{
- tcp_recved(cs->pcb, bufferLength);
- bufferLength = 0;
+ tcp_recved(cs->pcb, pb->tot_len);
+ dataAcknowledged = true;
}
- // Free pbuf (pbufs are thread-safe)
+ // Free all pbufs (pbufs are thread-safe)
if (pb != nullptr)
{
pbuf_free(pb);
diff --git a/src/Network.h b/src/Network.h
index 7c5fab49..b01619b3 100644
--- a/src/Network.h
+++ b/src/Network.h
@@ -27,10 +27,10 @@ Separated out from Platform.h by dc42 and extended by zpl
// Currently we set the MSS (in file network/lwipopts.h) to 1432 which matches the value used by most versions of Windows
// and therefore avoids additional memory use and fragmentation.
-const size_t NETWORK_TRANSACTION_COUNT = 16; // Number of NetworkTransactions to be used for network IO
+const size_t NETWORK_TRANSACTION_COUNT = 24; // Number of NetworkTransactions to be used for network IO
const uint32_t TCP_WRITE_TIMEOUT = 4000; // Miliseconds to wait for data we have written to be acknowledged
-const uint32_t TCP_MAX_SEND_RETRIES = 4; // How many times can we attempt to write data
+const uint32_t TCP_MAX_SEND_RETRIES = 8; // How many times can we attempt to write data
const uint8_t MAC_ADDRESS[6] = { 0xBE, 0xEF, 0xDE, 0xAD, 0xFE, 0xED }; // Need some sort of default...
const uint8_t IP_ADDRESS[4] = { 192, 168, 1, 10 };
@@ -52,26 +52,33 @@ class NetworkTransaction;
// ConnectionState structure that we use to track TCP connections. It is usually combined with NetworkTransactions.
struct ConnectionState
{
- tcp_pcb *pcb; // Connection PCB
- uint16_t localPort, remotePort; // Copy of the local and remote ports, because the PCB may be unavailable
- uint32_t remoteIPAddress; // Same for the remote IP address
- NetworkTransaction *sendingTransaction; // NetworkTransaction that is currently sending via this connection
- ConnectionState *next; // Next ConnectionState in this list
- bool persistConnection; // Do we expect this connection to stay alive?
+ tcp_pcb *volatile pcb; // Connection PCB
+ uint16_t localPort, remotePort; // Copy of the local and remote ports, because the PCB may be unavailable
+ uint32_t remoteIPAddress; // Same for the remote IP address
+ NetworkTransaction * volatile sendingTransaction; // NetworkTransaction that is currently sending via this connection
+ ConnectionState * volatile next; // Next ConnectionState in this list
+ bool persistConnection; // Do we expect this connection to stay alive?
+ volatile bool isTerminated; // Will be true if the connection has gone down unexpectedly (TCP RST)
void Init(tcp_pcb *p);
uint16_t GetLocalPort() const { return localPort; }
uint32_t GetRemoteIP() const { return remoteIPAddress; }
uint16_t GetRemotePort() const { return remotePort; }
+ bool IsConnected() const { return pcb != nullptr; }
+ bool IsTerminated() const { return isTerminated; }
+ void Terminate();
};
// Assign a status to each NetworkTransaction
enum TransactionStatus
{
+ released,
connected,
- dataReceiving,
- dataSending,
- disconnected
+ receiving,
+ sending,
+ disconnected,
+ deferred,
+ acquired
};
// Start with a class to hold input and output from the network that needs to be responded to.
@@ -84,10 +91,11 @@ class NetworkTransaction
NetworkTransaction(NetworkTransaction* n);
void Set(pbuf *p, ConnectionState* c, TransactionStatus s);
TransactionStatus GetStatus() const { return status; }
+ bool IsConnected() const;
bool HasMoreDataToRead() const { return readingPb != nullptr; }
bool Read(char& b);
- bool ReadBuffer(const char *&buffer, unsigned int &len);
+ bool ReadBuffer(const char *&buffer, size_t &len);
void Write(char b);
void Write(const char* s);
void Write(StringRef ref);
@@ -97,15 +105,13 @@ class NetworkTransaction
void Printf(const char *fmt, ...);
void SetFileToWrite(FileStore *file);
- void SetConnectionLost();
- bool LostConnection() const { return cs == nullptr || cs->pcb == nullptr; }
ConnectionState *GetConnection() const { return cs; }
uint16_t GetLocalPort() const;
uint32_t GetRemoteIP() const;
uint16_t GetRemotePort() const;
void Commit(bool keepConnectionAlive);
- void Defer();
+ void Defer(bool keepData);
void Discard();
private:
@@ -116,18 +122,16 @@ class NetworkTransaction
ConnectionState* cs;
NetworkTransaction* volatile next; // next NetworkTransaction in the list we are in
- NetworkTransaction* nextWrite; // next NetworkTransaction queued to write to assigned connection
+ NetworkTransaction* volatile nextWrite; // next NetworkTransaction queued to write to assigned connection
pbuf *pb, *readingPb; // received packet queue and a pointer to the pbuf being read from
- unsigned int bufferLength; // total length of the packet buffer
- unsigned int inputPointer; // amount of data already taken from the first packet buffer
+ size_t inputPointer; // amount of data already taken from the first packet buffer
OutputBuffer *sendBuffer;
OutputStack *sendStack;
- FileStore *fileBeingSent;
+ FileStore * volatile fileBeingSent;
- TransactionStatus status;
- bool closeRequested;
- bool waitingForDataConnection;
+ volatile TransactionStatus status;
+ volatile bool closeRequested, dataAcknowledged;
};
// The main network class that drives the network.
@@ -136,50 +140,54 @@ class Network
public:
friend class NetworkTransaction;
- void ReadPacket();
+ Network(Platform* p);
+ void Init();
+ void Exit() {}
+ void Spin();
+ void Interrupt();
+ void Diagnostics();
+
+ // Deal with LwIP
+
+ void ResetCallback();
bool ReceiveInput(pbuf *pb, ConnectionState *cs);
ConnectionState *ConnectionAccepted(tcp_pcb *pcb);
void ConnectionClosed(ConnectionState* cs, bool closeConnection);
bool ConnectionClosedGracefully(ConnectionState *cs);
- NetworkTransaction *GetTransaction(const ConnectionState *cs = nullptr);
- void WaitForDataConection();
+ bool Lock();
+ void Unlock();
+ bool InLwip() const;
+
+ // Global settings
const uint8_t *IPAddress() const;
void SetIPAddress(const uint8_t ipAddress[], const uint8_t netmask[], const uint8_t gateway[]);
+ void SetHostname(const char *name);
+
+ void Enable();
+ void Disable();
+ bool IsEnabled() const;
+
+ // Interfaces for the Webserver
+
+ NetworkTransaction *GetTransaction(const ConnectionState *cs = nullptr);
+
void OpenDataPort(uint16_t port);
uint16_t GetDataPort() const;
void CloseDataPort();
+ void SetHttpPort(uint16_t port);
+ uint16_t GetHttpPort() const;
+
void SaveDataConnection();
void SaveFTPConnection();
void SaveTelnetConnection();
- bool CanAcquireTransaction();
bool AcquireFTPTransaction();
bool AcquireDataTransaction();
bool AcquireTelnetTransaction();
- Network(Platform* p);
- void Init();
- void Exit() {}
- void Spin();
- void Interrupt();
- void Diagnostics();
-
- bool Lock();
- void Unlock();
- bool InLwip() const;
-
- void Enable();
- void Disable();
- bool IsEnabled() const;
-
- void SetHttpPort(uint16_t port);
- uint16_t GetHttpPort() const;
-
- void SetHostname(const char *name);
-
private:
Platform* platform;
@@ -195,19 +203,24 @@ class Network
enum { NetworkPreInitializing, NetworkPostInitializing, NetworkInactive, NetworkActive } state;
bool isEnabled;
- bool volatile readingData;
+ volatile bool resetCallback;
char hostname[16]; // Limit DHCP hostname to 15 characters + terminating 0
- ConnectionState *dataCs;
- ConnectionState *ftpCs;
- ConnectionState *telnetCs;
+ ConnectionState * volatile dataCs;
+ ConnectionState * volatile ftpCs;
+ ConnectionState * volatile telnetCs;
- ConnectionState * volatile freeConnections; // May be referenced by Ethernet ISR, hence it's volatile
+ ConnectionState * volatile freeConnections;
};
+inline bool NetworkTransaction::IsConnected() const
+{
+ return (cs != nullptr && cs->IsConnected());
+}
+
inline bool NetworkTransaction::CanWrite() const
{
- return (!LostConnection() && status != disconnected && status != dataSending);
+ return (IsConnected() && status != released);
}
#endif
diff --git a/src/OutputMemory.cpp b/src/OutputMemory.cpp
index a4bec44e..366c89a8 100644
--- a/src/OutputMemory.cpp
+++ b/src/OutputMemory.cpp
@@ -428,10 +428,10 @@ size_t OutputBuffer::EncodeReply(OutputBuffer *src, bool allowControlChars)
// Truncate an output buffer to free up more memory. Returns the number of released bytes.
-/*static */ size_t OutputBuffer::Truncate(OutputBuffer *buffer, size_t bytesNeeded)
+/*static */ size_t OutputBuffer::Truncate(OutputBuffer *buffer, size_t bytesNeeded )
{
- // Can we free up space from this chain?
- if (buffer == nullptr || buffer->Next() == nullptr)
+ // Can we free up space from this chain? Don't break it up if it's referenced anywhere else
+ if (buffer == nullptr || buffer->Next() == nullptr || buffer->IsReferenced())
{
// No
return 0;
diff --git a/src/Platform.cpp b/src/Platform.cpp
index 5283fdff..9b6bdba1 100644
--- a/src/Platform.cpp
+++ b/src/Platform.cpp
@@ -658,6 +658,7 @@ void Platform::ResetNvData()
#if FLASH_SAVE_ENABLED
nvData.magic = FlashData::magicValue;
+ nvData.version = FlashData::versionValue;
#endif
}
@@ -665,7 +666,7 @@ void Platform::ReadNvData()
{
#if FLASH_SAVE_ENABLED
DueFlashStorage::read(FlashData::nvAddress, &nvData, sizeof(nvData));
- if (nvData.magic != FlashData::magicValue)
+ if (nvData.magic != FlashData::magicValue || nvData.version != FlashData::versionValue)
{
// Nonvolatile data has not been initialized since the firmware was last written, so set up default values
ResetNvData();
@@ -706,20 +707,26 @@ void Platform::UpdateFirmware()
// The machine will be unresponsive for a few seconds, don't risk damaging the heaters...
reprap.EmergencyStop();
-
- // Step 1 - Write update binary to Flash
+ // Step 1 - Write update binary to Flash and overwrite the remaining space with zeros
+ // Leave the last 1KB of Flash memory untouched, so we can reuse the NvData after this update
char data[IFLASH_PAGE_SIZE];
int bytesRead;
for(uint32_t flashAddr = IAP_FLASH_START; flashAddr < IAP_FLASH_END; flashAddr += IFLASH_PAGE_SIZE)
{
bytesRead = iapFile->Read(data, IFLASH_PAGE_SIZE);
- if (bytesRead > 0 && flashAddr + bytesRead < IFLASH_ADDR + IFLASH_SIZE)
+ if (bytesRead > 0)
{
+ // Do we have to fill up the remaining buffer with zeros?
+ if (bytesRead != IFLASH_PAGE_SIZE)
+ {
+ memset(data + bytesRead, 0, sizeof(data[0]) * (IFLASH_PAGE_SIZE - bytesRead));
+ }
+
// Write one page at a time
cpu_irq_disable();
flash_unlock(flashAddr, flashAddr + IFLASH_PAGE_SIZE - 1, nullptr, nullptr);
- flash_write(flashAddr, data, bytesRead, 1);
+ flash_write(flashAddr, data, IFLASH_PAGE_SIZE, 1);
flash_lock(flashAddr, flashAddr + IFLASH_PAGE_SIZE - 1, nullptr, nullptr);
cpu_irq_enable();
@@ -732,13 +739,27 @@ void Platform::UpdateFirmware()
}
else
{
- // Cannot read any more or IAP binary exceeds 64KiB limit
- break;
+ // Empty write buffer so we can use it to fill up the remaining space
+ if (bytesRead != IFLASH_PAGE_SIZE)
+ {
+ memset(data, 0, sizeof(data[0]) * sizeof(data));
+ bytesRead = IFLASH_PAGE_SIZE;
+ }
+
+ // Fill up the remaining space
+ cpu_irq_disable();
+ flash_unlock(flashAddr, flashAddr + IFLASH_PAGE_SIZE - 1, nullptr, nullptr);
+ flash_write(flashAddr, data, IFLASH_PAGE_SIZE, 1);
+ flash_lock(flashAddr, flashAddr + IFLASH_PAGE_SIZE - 1, nullptr, nullptr);
+ cpu_irq_enable();
}
}
iapFile->Close();
- // Step 2 - Reallocate the vector table and program entry point to the new IAP binary
+ // Step 2 - Let the firmware do whatever is necessary before we exit this program
+ reprap.Exit();
+
+ // Step 3 - Reallocate the vector table and program entry point to the new IAP binary
// This does essentially what the Atmel AT02333 paper suggests (see 3.2.2 ff)
// Disable all IRQs
@@ -790,6 +811,16 @@ float Platform::Time()
void Platform::Exit()
{
+ // Close all files
+ for(size_t i = 0; i < MAX_FILES; i++)
+ {
+ while (files[i]->inUse)
+ {
+ files[i]->Close();
+ }
+ }
+
+ // Stop processing data
Message(GENERIC_MESSAGE, "Platform class exited.\n");
active = false;
}
@@ -859,6 +890,16 @@ 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();
+ }
+ }
+
// Write non-blocking data to the AUX line
OutputBuffer *auxOutputBuffer = auxOutput->GetFirstItem();
if (auxOutputBuffer != nullptr)
@@ -985,6 +1026,7 @@ void Platform::SoftwareReset(uint16_t reason)
// Record the reason for the software reset
SoftwareResetData temp;
temp.magic = SoftwareResetData::magicValue;
+ temp.version = SoftwareResetData::versionValue;
temp.resetReason = reason;
GetStackUsage(NULL, NULL, &temp.neverUsedRam);
@@ -1122,7 +1164,7 @@ void Platform::Diagnostics()
SoftwareResetData temp;
temp.magic = 0;
DueFlashStorage::read(SoftwareResetData::nvAddress, &temp, sizeof(SoftwareResetData));
- if (temp.magic == SoftwareResetData::magicValue)
+ 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]);
@@ -1328,6 +1370,7 @@ float Platform::GetTemperature(size_t heater, TempError* err) const
// See if we need to turn on the hot end fan
bool Platform::AnyHeaterHot(uint16_t heaters, float t) const
{
+ // Check tool heaters first
for (size_t h = 0; h < reprap.GetToolHeatersInUse(); ++h)
{
if (((1 << h) & heaters) != 0)
@@ -1350,6 +1393,17 @@ bool Platform::AnyHeaterHot(uint16_t heaters, float t) const
return true;
}
}
+
+ // Check the chamber heater as well
+ int8_t chamberHeater = reprap.GetHeat()->GetChamberHeater();
+ if (chamberHeater >= 0 && ((1 << (unsigned int)chamberHeater) & heaters) != 0)
+ {
+ const float ht = GetTemperature(chamberHeater);
+ if (ht >= t || ht < BAD_LOW_TEMPERATURE)
+ {
+ return true;
+ }
+ }
return false;
}
@@ -1843,7 +1897,7 @@ void Platform::Fan::Refresh()
void Platform::Fan::SetPwmFrequency(float p_freq)
{
- freq = (uint16_t)max<float>(1.0, min<float>(65535.0, p_freq));
+ freq = (uint16_t)constrain<float>(p_freq, 1.0, 65535.0);
Refresh();
}
@@ -1878,21 +1932,22 @@ void Platform::SetMACAddress(uint8_t mac[])
FileStore* Platform::GetFileStore(const char* directory, const char* fileName, bool write)
{
if (!fileStructureInitialised)
- return NULL;
+ {
+ return nullptr;
+ }
for (size_t i = 0; i < MAX_FILES; i++)
{
if (!files[i]->inUse)
{
- files[i]->inUse = true;
if (files[i]->Open(directory, fileName, write))
{
+ files[i]->inUse = true;
return files[i];
}
else
{
- files[i]->inUse = false;
- return NULL;
+ return nullptr;
}
}
}
@@ -1900,11 +1955,6 @@ FileStore* Platform::GetFileStore(const char* directory, const char* fileName, b
return NULL;
}
-MassStorage* Platform::GetMassStorage()
-{
- return massStorage;
-}
-
void Platform::Message(MessageType type, const char *message)
{
switch (type)
@@ -2083,7 +2133,7 @@ void Platform::Message(const MessageType type, OutputBuffer *buffer)
default:
// Everything else is unsupported (and probably not used)
OutputBuffer::ReleaseAll(buffer);
- MessageF(HOST_MESSAGE, "Warning: Unsupported Message call for type %u!\n", type);
+ MessageF(HOST_MESSAGE, "Error: Unsupported Message call for type %u!\n", type);
break;
}
}
diff --git a/src/Platform.h b/src/Platform.h
index bf23ab0e..1ab8a286 100644
--- a/src/Platform.h
+++ b/src/Platform.h
@@ -469,7 +469,7 @@ public:
friend class FileStore;
- MassStorage* GetMassStorage();
+ 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
@@ -623,39 +623,45 @@ private:
// These are the structures used to hold out non-volatile data.
// The SAM3X doesn't have EEPROM so we save the data to flash. This unfortunately means that it gets cleared
- // every time we reprogram the firmware. So there is no need to cater for writing one version of this
- // struct and reading back another.
+ // every time we reprogram the firmware via bossa, but it can be retained when firmware updates are performed
+ // via the web interface. That's why it's a good idea to implement versioning here - increase these values
+ // whenever the fields of the follwoing structs have changed.
struct SoftwareResetData
{
- static const uint16_t magicValue = 0x59B2; // value we use to recognise that all the flash data has been written
- static const uint32_t nvAddress = 0; // address in flash where we store the nonvolatile data
+ static const uint16_t magicValue = 0x7C5F; // value we use to recognise that all the flash data has been written
+ static const uint16_t versionValue = 1; // increment this whenever this struct changes
+ static const uint32_t nvAddress = 0;
- uint16_t magic;
- uint16_t resetReason; // this records why we did a software reset, for diagnostic purposes
- size_t neverUsedRam; // the amount of never used RAM at the last abnormal software reset
+ uint16_t magic;
+ uint16_t version;
+
+ uint16_t resetReason; // this records why we did a software reset, for diagnostic purposes
+ size_t neverUsedRam; // the amount of never used RAM at the last abnormal software reset
};
struct FlashData
{
- static const uint16_t magicValue = 0xA436; // value we use to recognise that the flash data has been written
- static const uint32_t nvAddress = SoftwareResetData::nvAddress + sizeof(struct SoftwareResetData);
-
- uint16_t magic;
-
- // The remaining data could alternatively be saved to SD card.
- // Note however that if we save them as G codes, we need to provide a way of saving IR and ultrasonic G31 parameters separately.
- ZProbeParameters switchZProbeParameters; // Z probe values for the endstop switch
- ZProbeParameters irZProbeParameters; // Z probe values for the IR sensor
- ZProbeParameters alternateZProbeParameters; // Z probe values for the alternate sensor
- int zProbeType; // the type of Z probe we are currently using
- bool zProbeAxes[AXES]; // Z probe is used for these axes
- PidParameters pidParams[HEATERS];
- byte ipAddress[4];
- byte netMask[4];
- byte gateWay[4];
- uint8_t macAddress[6];
- Compatibility compatibility;
+ static const uint16_t magicValue = 0xE6C4; // value we use to recognise that the flash data has been written
+ static const uint16_t versionValue = 1; // increment this whenever this struct changes
+ static const uint32_t nvAddress = SoftwareResetData::nvAddress + sizeof(struct SoftwareResetData);
+
+ uint16_t magic;
+ uint16_t version;
+
+ // The remaining data could alternatively be saved to SD card.
+ // Note however that if we save them as G codes, we need to provide a way of saving IR and ultrasonic G31 parameters separately.
+ ZProbeParameters switchZProbeParameters; // Z probe values for the endstop switch
+ ZProbeParameters irZProbeParameters; // Z probe values for the IR sensor
+ ZProbeParameters alternateZProbeParameters; // Z probe values for the alternate sensor
+ int zProbeType; // the type of Z probe we are currently using
+ bool zProbeAxes[AXES]; // Z probe is used for these axes
+ PidParameters pidParams[HEATERS];
+ byte ipAddress[4];
+ byte netMask[4];
+ byte gateWay[4];
+ uint8_t macAddress[6];
+ Compatibility compatibility;
};
struct Fan
@@ -1264,6 +1270,11 @@ inline void Platform::SetNozzleDiameter(float diameter)
nozzleDiameter = diameter;
}
+inline MassStorage* Platform::GetMassStorage() const
+{
+ return massStorage;
+}
+
/*static*/ inline void Platform::EnableWatchdog()
{
const uint32_t wdtTicks = 256; // number of watchdog ticks @ 32768Hz/128 before the watchdog times out (max 4095)
diff --git a/src/PrintMonitor.cpp b/src/PrintMonitor.cpp
index 5f0005cd..d4a895fd 100644
--- a/src/PrintMonitor.cpp
+++ b/src/PrintMonitor.cpp
@@ -590,7 +590,7 @@ bool PrintMonitor::GetFileInfo(const char *directory, const char *fileName, GCod
bool PrintMonitor::GetFileInfoResponse(const char *filename, OutputBuffer *&response)
{
// Poll file info for a specific file
- if (filename != nullptr)
+ if (filename != nullptr && filename[0] != 0)
{
GCodeFileInfo info;
if (!GetFileInfo("0:/", filename, info))
@@ -682,25 +682,17 @@ bool PrintMonitor::GetFileInfoResponse(const char *filename, OutputBuffer *&resp
return true;
}
+// May be called from ISR
void PrintMonitor::StopParsing(const char *filename)
{
- if (parseState == notParsing)
+ if (parseState != notParsing && StringEquals(filenameBeingParsed, filename))
{
- // We're not parsing anything, stop here
- return;
- }
-
- if (filenameBeingPrinted[0] != 0 && !printingFileParsed)
- {
- if (StringEquals(filename, filenameBeingPrinted))
+ if (!printingFileParsed)
{
// If this is the file we're parsing for internal purposes, don't bother with this request
return;
}
- }
- if (StringEquals(filenameBeingParsed, filename))
- {
parseState = notParsing;
fileBeingParsed->Close();
}
@@ -977,16 +969,19 @@ bool PrintMonitor::FindHeight(const char* buf, size_t len, float& height) const
{
if (zPos != 0)
{
- // Check special case of this code ending with ";E" - ignore such codes
- j = zPos;
- while (j < len - 2 && c != '\n')
+ // Check special case of this code ending with ";E" or "; E" - ignore such codes
+ for(j = zPos + 1; j < len - 3; j++)
{
- c = buf[++j];
- if (c == ';' && buf[j + 1] == 'E')
+ c = buf[j];
+ if (c == ';' && (buf[j + 1] == 'E' || buf[j + 2] == 'E'))
{
zPos = 0;
break;
}
+ if (c == '\n')
+ {
+ break;
+ }
}
if (zPos != 0)
diff --git a/src/PrintMonitor.h b/src/PrintMonitor.h
index ab96dcdb..8778a829 100644
--- a/src/PrintMonitor.h
+++ b/src/PrintMonitor.h
@@ -21,7 +21,7 @@ Licence: GPL
#define PRINTMONITOR_H
const FilePosition GCODE_HEADER_SIZE = 8192uL; // How many bytes to read from the header
-const FilePosition GCODE_FOOTER_SIZE = 128000uL; // How many bytes to read from the footer
+const FilePosition GCODE_FOOTER_SIZE = 192000uL; // How many bytes to read from the footer
const size_t GCODE_READ_SIZE = 1024; // How many bytes to read in one go in GetFileInfo() (should be a multiple of 4 for read efficiency)
const size_t GCODE_OVERLAP_SIZE = 100; // Size of the overlapping buffer for searching (should be a multple of 4 as well)
@@ -119,7 +119,7 @@ class PrintMonitor
float RawFilamentExtruded() const;
// We parse G-Code files in multiple stages. These variables hold the required information
- FileParseState parseState;
+ volatile FileParseState parseState;
char filenameBeingParsed[FILENAME_LENGTH];
FileStore *fileBeingParsed;
GCodeFileInfo parsedFileInfo;
diff --git a/src/RepRapFirmware.h b/src/RepRapFirmware.h
index a716bae0..33510529 100644
--- a/src/RepRapFirmware.h
+++ b/src/RepRapFirmware.h
@@ -31,7 +31,7 @@ Licence: GPL
#include "StringRef.h"
// Module numbers and names, used for diagnostics and debug
-enum Module
+enum Module : uint8_t
{
modulePlatform = 0,
moduleNetwork = 1,
diff --git a/src/Tool.cpp b/src/Tool.cpp
index 3de3c3cf..0e57c39d 100644
--- a/src/Tool.cpp
+++ b/src/Tool.cpp
@@ -271,12 +271,13 @@ void Tool::SetVariables(const float* standby, const float* active)
}
else
{
- if (active[heater] < reprap.GetPlatform()->GetTemperatureLimit())
+ const float temperatureLimit = reprap.GetPlatform()->GetTemperatureLimit();
+ if (active[heater] < temperatureLimit)
{
activeTemperatures[heater] = active[heater];
reprap.GetHeat()->SetActiveTemperature(heaters[heater], activeTemperatures[heater]);
}
- if (standby[heater] < reprap.GetPlatform()->GetTemperatureLimit())
+ if (standby[heater] < temperatureLimit)
{
standbyTemperatures[heater] = standby[heater];
reprap.GetHeat()->SetStandbyTemperature(heaters[heater], standbyTemperatures[heater]);
diff --git a/src/Tool.h b/src/Tool.h
index a8be4ed1..16210259 100644
--- a/src/Tool.h
+++ b/src/Tool.h
@@ -45,9 +45,8 @@ public:
void GetVariables(float* standby, float* active) const;
void DefineMix(float* m);
const float* GetMix() const;
- void TurnMixingOn();
- void TurnMixingOff();
- bool Mixing() const;
+ void SetMixing(bool b);
+ bool GetMixing() const;
float MaxFeedrate() const;
float InstantDv() const;
void Print(StringRef& reply);
@@ -125,17 +124,12 @@ inline const float* Tool::GetMix() const
return mix;
}
-inline void Tool::TurnMixingOn()
+inline void Tool::SetMixing(bool b)
{
- mixing = true;
+ mixing = b;
}
-inline void Tool::TurnMixingOff()
-{
- mixing = false;
-}
-
-inline bool Tool::Mixing() const
+inline bool Tool::GetMixing() const
{
return mixing;
}
diff --git a/src/Webserver.cpp b/src/Webserver.cpp
index 359f8566..1a4e2f74 100644
--- a/src/Webserver.cpp
+++ b/src/Webserver.cpp
@@ -92,7 +92,7 @@ const char* badEscapeResponse = "bad escape";
// Constructor and initialisation
Webserver::Webserver(Platform* p, Network *n) : platform(p), network(n), webserverActive(false),
- readingConnection(nullptr)
+ readingConnection(nullptr), readingConnectionTimestamp(0)
{
httpInterpreter = new HttpInterpreter(p, this, n);
ftpInterpreter = new FtpInterpreter(p, this, n);
@@ -117,9 +117,6 @@ void Webserver::Spin()
{
if (webserverActive)
{
- // Check if we can purge any HTTP sessions
- httpInterpreter->CheckSessions();
-
// Check if we can actually send something back to the client
if (OutputBuffer::GetBytesLeft(nullptr) == 0)
{
@@ -134,95 +131,130 @@ void Webserver::Spin()
return;
}
+ // Allow each ProtocolInterpreter to do something
+ httpInterpreter->Spin();
+ ftpInterpreter->Spin();
+ telnetInterpreter->Spin();
+
// See if we have new data to process
- NetworkTransaction *transaction = network->GetTransaction(readingConnection);
- if (transaction != nullptr)
+ currentTransaction = network->GetTransaction(readingConnection);
+ if (currentTransaction != nullptr)
{
- if (!transaction->LostConnection())
+ // Take care of different protocol types here
+ ProtocolInterpreter *interpreter;
+ uint16_t localPort = currentTransaction->GetLocalPort();
+ switch (localPort)
{
- // Take care of different protocol types here
- ProtocolInterpreter *interpreter;
- uint16_t localPort = transaction->GetLocalPort();
- switch (localPort)
- {
- case FTP_PORT: /* FTP */
- interpreter = ftpInterpreter;
- break;
+ case FTP_PORT: /* FTP */
+ interpreter = ftpInterpreter;
+ break;
- case TELNET_PORT: /* Telnet */
- interpreter = telnetInterpreter;
- break;
+ case TELNET_PORT: /* Telnet */
+ interpreter = telnetInterpreter;
+ break;
- default: /* HTTP and FTP data */
- if (localPort == network->GetHttpPort())
- {
- interpreter = httpInterpreter;
- }
- else
- {
- interpreter = ftpInterpreter;
- }
- break;
- }
+ default: /* HTTP and FTP data */
+ if (localPort == network->GetHttpPort())
+ {
+ interpreter = httpInterpreter;
+ }
+ else
+ {
+ interpreter = ftpInterpreter;
+ }
+ break;
+ }
- // For protocols other than HTTP it is important to send a HELO message
- TransactionStatus status = transaction->GetStatus();
- if (status == connected)
- {
- interpreter->ConnectionEstablished();
- transaction->Discard();
- }
- // Graceful disconnects are handled here, because prior NetworkTransactions might still contain valid
- // data. That's why it's a bad idea to close these connections immediately in the Network class.
- else if (status == disconnected)
- {
- // This will call the disconnect events and effectively close the connection
- transaction->Discard();
- }
- // Check for fast uploads
- else if (interpreter->DoingFastUpload())
- {
- interpreter->DoFastUpload(transaction);
- }
- // Check if we need to send data to a Telnet client
- else if (interpreter == telnetInterpreter && telnetInterpreter->HasDataToSend())
+ // See if we have to print some debug info
+ if (reprap.Debug(moduleWebserver))
+ {
+ const char *type;
+ switch (currentTransaction->GetStatus())
{
- telnetInterpreter->SendGCodeReply(transaction);
+ case released: type = "released"; break;
+ case connected: type = "connected"; break;
+ case receiving: type = "receiving"; break;
+ case sending: type = "sending"; break;
+ case disconnected: type = "disconnected"; break;
+ case deferred: type = "deferred"; break;
+ case acquired: type = "acquired"; break;
+ default: type = "unknown"; break;
}
- // Process other messages (if we can)
- else if (interpreter != httpInterpreter || httpInterpreter->IsReady())
+ platform->MessageF(HOST_MESSAGE, "Incoming transaction: Type %s at local port %d (remote port %d)\n",
+ type, localPort, currentTransaction->GetRemotePort());
+ }
+
+ // For protocols other than HTTP it is important to send a HELO message
+ TransactionStatus status = currentTransaction->GetStatus();
+ if (status == connected)
+ {
+ interpreter->ConnectionEstablished();
+ }
+ // Graceful disconnects are handled here, because prior NetworkTransactions might still contain valid
+ // data. That's why it's a bad idea to close these connections immediately in the Network class.
+ else if (status == disconnected)
+ {
+ // This will call the disconnect events and effectively close the connection
+ currentTransaction->Discard();
+ }
+ // Check for fast uploads via this connection
+ else if (interpreter->DoingFastUpload())
+ {
+ interpreter->DoFastUpload();
+ }
+ // Check if we need to send data to a Telnet client
+ else if (interpreter == telnetInterpreter && telnetInterpreter->HasDataToSend())
+ {
+ telnetInterpreter->SendGCodeReply();
+ }
+ // Process other messages (if we can)
+ else if (interpreter != httpInterpreter || httpInterpreter->IsReady())
+ {
+ for(size_t i = 0; i < 500; i++)
{
- for(size_t i = 0; i < 500; i++)
+ char c;
+ if (currentTransaction->Read(c))
+ {
+ // Each ProtocolInterpreter must take care of the current NetworkTransaction by
+ // calling either Commit(), Discard() or Defer()
+ if (interpreter->CharFromClient(c))
+ {
+ readingConnection = nullptr;
+ break;
+ }
+ }
+ else
{
- char c;
- if (transaction->Read(c))
+ // We ran out of data before finding a complete request.
+ // This happens when the incoming message length exceeds the TCP MSS.
+ // Check if we need to process another packet on the same connection.
+ if (interpreter->NeedMoreData())
{
- // Each ProtocolInterpreter must take care of the current NetworkTransaction and remove
- // it from the ready transactions by either calling SendAndClose() or CloseRequest().
- if (interpreter->CharFromClient(c))
- {
- readingConnection = nullptr;
- break;
- }
+ readingConnection = currentTransaction->GetConnection();
+ readingConnectionTimestamp = millis();
}
else
{
- // We ran out of data before finding a complete request.
- // This happens when the incoming message length exceeds the TCP MSS.
- // Check if we need to process another packet on the same connection.
- readingConnection = (interpreter->NeedMoreData()) ? transaction->GetConnection() : nullptr;
- transaction->Discard();
- break;
+ readingConnection = nullptr;
}
+
+ currentTransaction->Discard();
+ break;
}
}
- // else the HTTP server is not ready
}
- else
+ // else the HTTP server is not ready
+ }
+ else if (readingConnection != nullptr && millis() - readingConnectionTimestamp > processTimeout)
+ {
+ if (reprap.Debug(moduleWebserver))
{
- platform->MessageF(HOST_MESSAGE, "Webserver: Skipping zombie transaction with status %d\n", transaction->GetStatus());
- transaction->Discard();
+ platform->MessageF(HOST_MESSAGE, "Timing out connection at local port %d (remote port %d)\n",
+ readingConnection->GetLocalPort(), readingConnection->GetRemotePort());
}
+
+ // If the reading connection blocks too long, reset it. The connection closed handler will do everything else
+ readingConnection->Terminate();
}
network->Unlock(); // unlock LWIP again
}
@@ -233,8 +265,9 @@ void Webserver::Exit()
{
httpInterpreter->CancelUpload();
ftpInterpreter->CancelUpload();
+ //telnetInterpreter->CancelUpload(); // Telnet doesn't support fast file uploads
- platform->Message(GENERIC_MESSAGE, "Webserver class exited.\n");
+ platform->Message(HOST_MESSAGE, "Webserver class exited.\n");
webserverActive = false;
}
@@ -317,14 +350,11 @@ uint16_t Webserver::GetGCodeBufferSpace(const WebSource source) const
}
// Handle immediate disconnects here (cs will be freed after this call)
+// May be called by ISR, but not while LwIP is NOT locked
void Webserver::ConnectionLost(const ConnectionState *cs)
{
- // See which connection caused this event
- uint32_t remoteIP = cs->GetRemoteIP();
- uint16_t remotePort = cs->GetRemotePort();
- uint16_t localPort = cs->GetLocalPort();
-
// Inform protocol handlers that this connection has been lost
+ uint16_t localPort = cs->GetLocalPort();
ProtocolInterpreter *interpreter;
switch (localPort)
{
@@ -348,15 +378,16 @@ void Webserver::ConnectionLost(const ConnectionState *cs)
break;
}
- platform->MessageF(HOST_MESSAGE, "Error: Webserver should handle disconnect event at local port %d, but no handler was found!\n", localPort);
+ platform->MessageF(GENERIC_MESSAGE, "Error: Webserver should handle disconnect event at local port %d, but no handler was found!\n", localPort);
return;
}
+ // Print some debug information and notify the protocol interpreter
if (reprap.Debug(moduleWebserver))
{
- platform->MessageF(HOST_MESSAGE, "ConnectionLost called for local port %d (remote port %d)\n", localPort, remotePort);
+ platform->MessageF(HOST_MESSAGE, "ConnectionLost called for local port %d (remote port %d)\n", localPort, cs->GetRemotePort());
}
- interpreter->ConnectionLost(remoteIP, remotePort, localPort);
+ interpreter->ConnectionLost(cs);
// If our reading connection is lost, it will be no longer important which connection is read from first.
if (cs == readingConnection)
@@ -379,49 +410,77 @@ ProtocolInterpreter::ProtocolInterpreter(Platform *p, Webserver *ws, Network *n)
filenameBeingUploaded[0] = 0;
}
-// Start writing to a new file
-bool ProtocolInterpreter::StartUpload(FileStore *file)
+void ProtocolInterpreter::Spin()
{
- CancelUpload();
+ // We cannot safely access the SD card in ISRs, so check if we have to close them here
+ if (uploadState == uploadError)
+ {
+ if (fileBeingUploaded.IsLive())
+ {
+ fileBeingUploaded.Close();
+ }
+ if (filenameBeingUploaded[0] != 0)
+ {
+ platform->GetMassStorage()->Delete(FS_PREFIX, filenameBeingUploaded);
+ }
+
+ uploadState = notUploading;
+ filenameBeingUploaded[0] = 0;
+ }
+}
+void ProtocolInterpreter::ConnectionEstablished()
+{
+ // Don't care about incoming connections by default
+ webserver->currentTransaction->Discard();
+}
+
+// Start writing to a new file
+bool ProtocolInterpreter::StartUpload(FileStore *file, const char *fileName)
+{
if (file != nullptr)
{
fileBeingUploaded.Set(file);
+ strncpy(filenameBeingUploaded, fileName, ARRAY_SIZE(filenameBeingUploaded));
+ filenameBeingUploaded[ARRAY_UPB(filenameBeingUploaded)] = 0;
+
uploadState = uploadOK;
return true;
}
- uploadState = uploadError;
- platform->Message(HOST_MESSAGE, "Could not open file while starting upload!\n");
+ platform->Message(GENERIC_MESSAGE, "Error: Could not open file while starting upload!\n");
return false;
}
void ProtocolInterpreter::CancelUpload()
{
- if (fileBeingUploaded.IsLive())
+ if (uploadState == uploadOK)
{
- fileBeingUploaded.Close(); // cancel any pending file upload
- if (strlen(filenameBeingUploaded) != 0)
- {
- platform->GetMassStorage()->Delete(FS_PREFIX, filenameBeingUploaded);
- }
+ // Do the file handling next time when Spin is called
+ uploadState = uploadError;
}
- filenameBeingUploaded[0] = 0;
- uploadState = notUploading;
}
-void ProtocolInterpreter::DoFastUpload(NetworkTransaction *transaction)
+void ProtocolInterpreter::DoFastUpload()
{
+ NetworkTransaction *transaction = webserver->currentTransaction;
+
const char *buffer;
- unsigned int len;
+ size_t len;
if (transaction->ReadBuffer(buffer, len))
{
+ // See if we can output a debug message
+ if (reprap.Debug(moduleWebserver))
+ {
+ platform->MessageF(HOST_MESSAGE, "Writing %u bytes of upload data\n", len);
+ }
+
// Writing data usually takes a while, so keep LwIP running while this is being done
network->Unlock();
if (!fileBeingUploaded.Write(buffer, len))
{
- platform->Message(HOST_MESSAGE, "Could not write upload data!\n");
- uploadState = uploadError;
+ platform->Message(GENERIC_MESSAGE, "Error: Could not write upload data!\n");
+ CancelUpload();
while (!network->Lock());
transaction->Commit(false);
@@ -430,45 +489,48 @@ void ProtocolInterpreter::DoFastUpload(NetworkTransaction *transaction)
while (!network->Lock());
}
- if (!transaction->HasMoreDataToRead())
+ if (uploadState != uploadOK || !transaction->HasMoreDataToRead())
{
transaction->Discard();
}
}
-void ProtocolInterpreter::FinishUpload(uint32_t fileLength)
+bool ProtocolInterpreter::FinishUpload(uint32_t fileLength)
{
// Flush remaining data for FSO
if (uploadState == uploadOK && !fileBeingUploaded.Flush())
{
uploadState = uploadError;
- platform->Message(HOST_MESSAGE, "Could not flush remaining data while finishing upload!\n");
+ platform->Message(GENERIC_MESSAGE, "Error: Could not flush remaining data while finishing upload!\n");
}
// Check the file length is as expected
if (uploadState == uploadOK && fileLength != 0 && fileBeingUploaded.Length() != fileLength)
{
uploadState = uploadError;
- platform->MessageF(HOST_MESSAGE, "Uploaded file size is different (%u vs. expected %u Bytes)!\n", fileBeingUploaded.Length(), fileLength);
+ platform->MessageF(GENERIC_MESSAGE, "Error: Uploaded file size is different (%u vs. expected %u bytes)!\n", fileBeingUploaded.Length(), fileLength);
}
// Close the file
- if (!fileBeingUploaded.Close())
+ if (fileBeingUploaded.IsLive())
{
- uploadState = uploadError;
- platform->Message(HOST_MESSAGE, "Could not close the upload file while finishing upload!\n");
+ fileBeingUploaded.Close();
}
- // Delete file if an error has occurred
- if (uploadState == uploadError && strlen(filenameBeingUploaded) != 0)
+ // Delete the file again if an error has occurred
+ if (uploadState == uploadError && filenameBeingUploaded[0] != 0)
{
platform->GetMassStorage()->Delete(FS_PREFIX, filenameBeingUploaded);
}
+
+ // Clean up again
+ bool success = (uploadState == uploadOK);
+ uploadState = notUploading;
filenameBeingUploaded[0] = 0;
+ return success;
}
-
//********************************************************************************************
//
// *********************** HTTP interpreter for the Webserver class **************************
@@ -491,12 +553,54 @@ void Webserver::HttpInterpreter::Diagnostics()
platform->MessageF(GENERIC_MESSAGE, "HTTP sessions: %d of %d\n", numSessions, maxHttpSessions);
}
+void Webserver::HttpInterpreter::Spin()
+{
+ // Deal with aborted uploads
+ ProtocolInterpreter::Spin();
+
+ // Verify HTTP sessions
+ const uint32_t now = millis();
+ for(int i = numSessions - 1; i >= 0; i--)
+ {
+ if (sessions[i].isPostUploading)
+ {
+ // Check for cancelled POST uploads
+ if (uploadState != uploadOK)
+ {
+ sessions[i].isPostUploading = false;
+ sessions[i].lastQueryTime = millis();
+ }
+ }
+ else if ((now - sessions[i].lastQueryTime) > httpSessionTimeout)
+ {
+ // Check for timed out sessions
+ for(size_t k = i + 1; k < numSessions; k++)
+ {
+ memcpy(&sessions[k - 1], &sessions[k], sizeof(HttpSession));
+ }
+ numSessions--;
+ clientsServed++; // assume the disconnected client hasn't fetched the G-Code reply yet
+ }
+ }
+
+ // If we cannot send the G-Code reply to anyone, we may free up some run-time space by dumping it
+ if (numSessions == 0 || clientsServed >= numSessions)
+ {
+ while (!gcodeReply->IsEmpty())
+ {
+ OutputBuffer::ReleaseAll(gcodeReply->Pop());
+ }
+ clientsServed = 0;
+ }
+
+}
+
// File Uploads
bool Webserver::HttpInterpreter::DoingFastUpload() const
{
- uint32_t remoteIP = network->GetTransaction()->GetRemoteIP();
- uint16_t remotePort = network->GetTransaction()->GetRemotePort();
+ uint32_t remoteIP = webserver->currentTransaction->GetRemoteIP();
+ uint16_t remotePort = webserver->currentTransaction->GetRemotePort();
for(size_t i = 0; i < numSessions; i++)
{
if (sessions[i].ip == remoteIP && sessions[i].isPostUploading)
@@ -508,18 +612,20 @@ bool Webserver::HttpInterpreter::DoingFastUpload() const
return false;
}
-void Webserver::HttpInterpreter::DoFastUpload(NetworkTransaction *transaction)
+void Webserver::HttpInterpreter::DoFastUpload()
{
+ NetworkTransaction *transaction = webserver->currentTransaction;
+
// Write some data on the SD card
const char *buffer;
- unsigned int len;
+ size_t len;
if (transaction->ReadBuffer(buffer, len))
{
network->Unlock();
if (!fileBeingUploaded.Write(buffer, len))
{
- platform->Message(HOST_MESSAGE, "Could not write upload data!\n");
- uploadState = uploadError;
+ platform->Message(GENERIC_MESSAGE, "Error: Could not write upload data!\n");
+ CancelUpload();
while (!network->Lock());
SendJsonResponse("upload");
@@ -539,6 +645,7 @@ void Webserver::HttpInterpreter::DoFastUpload(NetworkTransaction *transaction)
if (sessions[i].ip == remoteIP && sessions[i].isPostUploading)
{
sessions[i].isPostUploading = false;
+ sessions[i].lastQueryTime = millis();
break;
}
}
@@ -546,35 +653,20 @@ void Webserver::HttpInterpreter::DoFastUpload(NetworkTransaction *transaction)
// We're done, flush the remaining upload data and send the JSON response
FinishUpload(postFileLength);
SendJsonResponse("upload");
- uploadState = notUploading;
}
- else if (!transaction->HasMoreDataToRead())
+ else if (uploadState != uploadOK || !transaction->HasMoreDataToRead())
{
+ // We cannot read any more, discard the transaction again
transaction->Discard();
}
}
-void Webserver::HttpInterpreter::CancelUpload()
-{
- for(size_t i = 0; i < numSessions; i++)
- {
- if (sessions[i].isPostUploading)
- {
- sessions[i].isPostUploading = false;
- sessions[i].lastQueryTime = millis();
- break;
- }
- }
-
- ProtocolInterpreter::CancelUpload();
-}
-
// Output to the client
// Start sending a file or a JSON response.
void Webserver::HttpInterpreter::SendFile(const char* nameOfFileToSend)
{
- NetworkTransaction *transaction = network->GetTransaction();
+ NetworkTransaction *transaction = webserver->currentTransaction;
if (nameOfFileToSend[0] == '/')
{
@@ -642,10 +734,11 @@ void Webserver::HttpInterpreter::SendFile(const char* nameOfFileToSend)
transaction->Commit(false);
}
-void Webserver::HttpInterpreter::SendConfigFile(NetworkTransaction *transaction)
+void Webserver::HttpInterpreter::SendConfigFile()
{
FileStore *configFile = platform->GetFileStore(platform->GetSysDir(), platform->GetConfigFile(), false);
+ NetworkTransaction *transaction = webserver->currentTransaction;
transaction->Write("HTTP/1.1 200 OK\n");
transaction->Write("Cache-Control: no-cache, no-store, must-revalidate\n");
transaction->Write("Pragma: no-cache\n");
@@ -657,7 +750,7 @@ void Webserver::HttpInterpreter::SendConfigFile(NetworkTransaction *transaction)
transaction->Commit(false);
}
-void Webserver::HttpInterpreter::SendGCodeReply(NetworkTransaction *transaction)
+void Webserver::HttpInterpreter::SendGCodeReply()
{
// Do we need to keep the G-Code reply for other clients?
bool clearReply = false;
@@ -683,6 +776,7 @@ void Webserver::HttpInterpreter::SendGCodeReply(NetworkTransaction *transaction)
}
// Send the whole G-Code reply as plain text to the client
+ NetworkTransaction *transaction = webserver->currentTransaction;
transaction->Write("HTTP/1.1 200 OK\n");
transaction->Write("Cache-Control: no-cache, no-store, must-revalidate\n");
transaction->Write("Pragma: no-cache\n");
@@ -702,38 +796,37 @@ void Webserver::HttpInterpreter::SendGCodeReply(NetworkTransaction *transaction)
void Webserver::HttpInterpreter::SendJsonResponse(const char* command)
{
- NetworkTransaction *transaction = network->GetTransaction();
-
// Try to authorize the user automatically to retain compatibility with the old web interface
if (!IsAuthenticated() && reprap.NoPasswordSet())
{
Authenticate();
}
- // rr_reply is treated differently, because it (currently) responds as "text/plain"
- if (IsAuthenticated() && StringEquals(command, "reply"))
+ // Handle "text/plain" requests
+ if (IsAuthenticated())
{
- SendGCodeReply(transaction);
- return;
- }
+ if (StringEquals(command, "reply")) // rr_reply
+ {
+ SendGCodeReply();
+ return;
+ }
- // rr_configfile sends the config as plain text well
- if (IsAuthenticated() && StringEquals(command, "configfile"))
- {
- SendConfigFile(transaction);
- return;
+ if (StringEquals(command, "configfile")) // rr_configfile
+ {
+ SendConfigFile();
+ return;
+ }
}
- // We need a valid output buffer to process this request...
+ // Try to process a request for JSON responses
OutputBuffer *jsonResponse;
if (!OutputBuffer::Allocate(jsonResponse))
{
- // Should never happen
- network->GetTransaction()->Commit(false);
+ // Reset the connection immediately if we cannot write any data. Should never happen
+ webserver->currentTransaction->GetConnection()->Terminate();
return;
}
- // See if we can find a suitable JSON response
bool keepOpen = false;
bool mayKeepOpen;
bool found;
@@ -746,10 +839,11 @@ void Webserver::HttpInterpreter::SendJsonResponse(const char* command)
found = GetJsonResponse(command, jsonResponse, qualifiers[0].key, qualifiers[0].value, qualifiers[1].key - qualifiers[0].value - 1, mayKeepOpen);
}
- // Check the special case of a deferred request
- if (processingDeferredRequest)
+ // Check the special case of a deferred request (rr_fileinfo)
+ NetworkTransaction *transaction = webserver->currentTransaction;
+ if (transaction->GetStatus() == deferred || transaction->GetStatus() == sending)
{
- // GetJsonResponse() must free the allocated OutputBuffer before we get here
+ OutputBuffer::Release(jsonResponse);
return;
}
@@ -796,12 +890,12 @@ void Webserver::HttpInterpreter::SendJsonResponse(const char* command)
bool Webserver::HttpInterpreter::IsReady()
{
- // We want to send a response, but we need memory for that. If there isn't enough available, see if we can truncate the G-Code reply
+ // We want to send a response, but we need memory for that. Check if we have to truncate the G-Code reply
while (OutputBuffer::GetBytesLeft(nullptr) < minHttpResponseSize)
{
if (gcodeReply->IsEmpty())
{
- // We cannot truncate any G-Code reply, so try again later
+ // We cannot truncate any G-Code reply and don't have enough free space, try again later
return false;
}
@@ -812,10 +906,20 @@ bool Webserver::HttpInterpreter::IsReady()
}
}
- // If we're already processing a request, we must not parse its content again
- if (processingDeferredRequest)
+ // Are we still processing a deferred request?
+ if (processingDeferredRequest && deferredRequestConnection == webserver->currentTransaction->GetConnection())
{
- ProcessMessage();
+ if (deferredRequestConnection->IsConnected())
+ {
+ // Process more of this request
+ ProcessDeferredRequest();
+ }
+ else
+ {
+ // Don't bother with this request if the connection has been closed.
+ // We expect a "disconnected" transaction to report this later, so don't clean up anything here
+ webserver->currentTransaction->Discard();
+ }
return false;
}
return true;
@@ -869,8 +973,7 @@ bool Webserver::HttpInterpreter::GetJsonResponse(const char* request, OutputBuff
if (StringEquals(request, "disconnect"))
{
- RemoveAuthentication();
- response->copy("{\"err\":0}");
+ response->printf("{\"err\":%d}", RemoveAuthentication() ? 0 : 1);
}
else if (StringEquals(request, "status"))
{
@@ -901,7 +1004,7 @@ bool Webserver::HttpInterpreter::GetJsonResponse(const char* request, OutputBuff
}
else if (StringEquals(request, "upload"))
{
- response->printf("{\"err\":%d}", (uploadState == uploadOK && uploadedBytes == postFileLength) ? 0 : 1);
+ response->printf("{\"err\":%d}", (uploadedBytes == postFileLength) ? 0 : 1);
}
else if (StringEquals(request, "delete") && StringEquals(key, "name"))
{
@@ -924,15 +1027,27 @@ bool Webserver::HttpInterpreter::GetJsonResponse(const char* request, OutputBuff
}
else if (StringEquals(request, "fileinfo"))
{
- // This may take a while before it returns, so allow LwIP to send ACKs while we're waiting for it
- network->Unlock();
- OutputBuffer::Release(response);
- processingDeferredRequest = !reprap.GetPrintMonitor()->GetFileInfoResponse(StringEquals(key, "name") ? value : nullptr, response);
- while (!network->Lock()); // This won't block for long
-
if (processingDeferredRequest)
{
- network->GetTransaction()->Defer();
+ // Don't allow multiple requests to be processed at once
+ webserver->currentTransaction->Defer(true);
+ }
+ else
+ {
+ if (StringEquals(qualifiers[0].key, "name"))
+ {
+ // Regular rr_fileinfo?name=xxx call
+ strncpy(filenameBeingProcessed, value, ARRAY_SIZE(filenameBeingProcessed));
+ filenameBeingProcessed[ARRAY_UPB(filenameBeingProcessed)] = 0;
+ }
+ else
+ {
+ // Simple rr_fileinfo call to get info about the file being printed
+ filenameBeingProcessed[0] = 0;
+ }
+
+ deferredRequestConnection = webserver->currentTransaction->GetConnection();
+ ProcessDeferredRequest();
}
}
else if (StringEquals(request, "move"))
@@ -972,11 +1087,6 @@ bool Webserver::HttpInterpreter::GetJsonResponse(const char* request, OutputBuff
return found;
}
-void Webserver::HttpInterpreter::GetJsonUploadResponse(OutputBuffer *response)
-{
- response->printf("{\"ubuff\":%u,\"err\":%d}", webUploadBufferSize, (uploadState == uploadOK) ? 0 : 1);
-}
-
void Webserver::HttpInterpreter::ResetState()
{
clientPointer = 0;
@@ -985,12 +1095,11 @@ void Webserver::HttpInterpreter::ResetState()
numQualKeys = 0;
numHeaderKeys = 0;
commandWords[0] = clientMessage;
- processingDeferredRequest = false;
}
bool Webserver::HttpInterpreter::NeedMoreData()
{
- if (!IsAuthenticated() && (!numCommandWords || !StringEquals(commandWords[0], "connect")))
+ if (!IsAuthenticated() && (numCommandWords == 0 || !StringEquals(commandWords[0], "connect")))
{
// It makes very little sense to allow unknown connections to block our HTTP reader
ResetState();
@@ -999,20 +1108,23 @@ bool Webserver::HttpInterpreter::NeedMoreData()
return true;
}
-void Webserver::HttpInterpreter::ConnectionLost(uint32_t remoteIP, uint16_t remotePort, uint16_t localPort)
+// May be called from ISR!
+void Webserver::HttpInterpreter::ConnectionLost(const ConnectionState *cs)
{
- // If the connection was lost before the request had been completed, reset our state here
- if (webserver->readingConnection != nullptr && webserver->readingConnection->GetRemotePort() == remotePort)
+ // Make sure deferred requests are cancelled
+ if (processingDeferredRequest && deferredRequestConnection == cs)
{
- if (processingDeferredRequest)
+ if (filenameBeingProcessed[0] != 0)
{
- if (numQualKeys != 0 && StringEquals(qualifiers[0].key, "name"))
- {
- // If we're still parsing a file while the disconnect occurred, stop it
- reprap.GetPrintMonitor()->StopParsing(qualifiers[0].value);
- }
+ // Only stop the parsing process if the filename is valid
+ reprap.GetPrintMonitor()->StopParsing(filenameBeingProcessed);
}
+ processingDeferredRequest = false;
+ }
+ // If the connection was lost before the request could be parsed, reset our state here
+ if (webserver->readingConnection == cs)
+ {
ResetState();
}
@@ -1020,6 +1132,8 @@ void Webserver::HttpInterpreter::ConnectionLost(uint32_t remoteIP, uint16_t remo
// because the client *might* have two instances of the web interface running.
if (uploadState == uploadOK)
{
+ const uint32_t remoteIP = cs->GetRemoteIP();
+ const uint16_t remotePort = cs->GetRemotePort();
for(size_t i = 0; i < numSessions; i++)
{
if (sessions[i].ip == remoteIP && sessions[i].isPostUploading && sessions[i].postPort == remotePort)
@@ -1028,6 +1142,7 @@ void Webserver::HttpInterpreter::ConnectionLost(uint32_t remoteIP, uint16_t remo
{
platform->MessageF(HOST_MESSAGE, "POST upload for '%s' has been cancelled!\n", filenameBeingUploaded);
}
+ sessions[i].isPostUploading = false;
CancelUpload();
break;
}
@@ -1378,11 +1493,7 @@ bool Webserver::HttpInterpreter::ProcessMessage()
SendFile(commandWords[1]);
}
- if (!processingDeferredRequest)
- {
- // Usually we're done here, but we must process deferred requests multiple times
- ResetState();
- }
+ ResetState();
return true;
}
else if (IsAuthenticated() && StringEquals(commandWords[0], "POST"))
@@ -1394,7 +1505,7 @@ bool Webserver::HttpInterpreter::ProcessMessage()
if (numQualKeys > 0 && StringEquals(qualifiers[0].key, "name"))
{
// We cannot upload more than one file at once
- if (uploadState == uploadOK)
+ if (IsUploading())
{
return RejectMessage("cannot upload more than one file at once");
}
@@ -1419,7 +1530,7 @@ bool Webserver::HttpInterpreter::ProcessMessage()
// Start a new file upload
FileStore *file = platform->GetFileStore(FS_PREFIX, qualifiers[0].value, true);
- if (!StartUpload(file))
+ if (!StartUpload(file, qualifiers[0].value))
{
return RejectMessage("could not start file upload");
}
@@ -1430,11 +1541,9 @@ bool Webserver::HttpInterpreter::ProcessMessage()
}
uploadedBytes = 0;
- strncpy(filenameBeingUploaded, qualifiers[0].value, ARRAY_SIZE(filenameBeingUploaded));
- filenameBeingUploaded[ARRAY_UPB(filenameBeingUploaded)] = 0;
-
- uint32_t remoteIP = network->GetTransaction()->GetRemoteIP();
- uint16_t remotePort = network->GetTransaction()->GetRemotePort();
+ // Keep track of the connection that is now uploading
+ uint32_t remoteIP = webserver->currentTransaction->GetRemoteIP();
+ uint16_t remotePort = webserver->currentTransaction->GetRemotePort();
for(size_t i = 0; i < numSessions; i++)
{
if (sessions[i].ip == remoteIP)
@@ -1462,7 +1571,7 @@ bool Webserver::HttpInterpreter::RejectMessage(const char* response, unsigned in
{
platform->MessageF(HOST_MESSAGE, "Webserver: rejecting message with: %s\n", response);
- NetworkTransaction *transaction = network->GetTransaction();
+ NetworkTransaction *transaction = webserver->currentTransaction;
transaction->Printf("HTTP/1.1 %u %s\nConnection: close\n\n", code, response);
transaction->Commit(false);
@@ -1476,7 +1585,7 @@ bool Webserver::HttpInterpreter::Authenticate()
{
if (numSessions < maxHttpSessions)
{
- sessions[numSessions].ip = network->GetTransaction()->GetRemoteIP();
+ sessions[numSessions].ip = webserver->currentTransaction->GetRemoteIP();
sessions[numSessions].lastQueryTime = millis();
sessions[numSessions].isPostUploading = false;
numSessions++;
@@ -1487,7 +1596,7 @@ bool Webserver::HttpInterpreter::Authenticate()
bool Webserver::HttpInterpreter::IsAuthenticated() const
{
- const uint32_t remoteIP = network->GetTransaction()->GetRemoteIP();
+ const uint32_t remoteIP = webserver->currentTransaction->GetRemoteIP();
for(size_t i = 0; i < numSessions; i++)
{
if (sessions[i].ip == remoteIP)
@@ -1500,7 +1609,7 @@ bool Webserver::HttpInterpreter::IsAuthenticated() const
void Webserver::HttpInterpreter::UpdateAuthentication()
{
- const uint32_t remoteIP = network->GetTransaction()->GetRemoteIP();
+ const uint32_t remoteIP = webserver->currentTransaction->GetRemoteIP();
for(size_t i = 0; i < numSessions; i++)
{
if (sessions[i].ip == remoteIP)
@@ -1511,49 +1620,28 @@ void Webserver::HttpInterpreter::UpdateAuthentication()
}
}
-void Webserver::HttpInterpreter::RemoveAuthentication()
+bool Webserver::HttpInterpreter::RemoveAuthentication()
{
- const uint32_t remoteIP = network->GetTransaction()->GetRemoteIP();
+ const uint32_t remoteIP = webserver->currentTransaction->GetRemoteIP();
for(int i=(int)numSessions - 1; i>=0; i--)
{
if (sessions[i].ip == remoteIP)
{
- for (size_t k = i + 1; k < numSessions; ++k)
+ if (sessions[i].isPostUploading)
{
- memcpy(&sessions[k - 1], &sessions[k], sizeof(HttpSession));
+ // Don't allow sessions with active POST uploads to be removed
+ return false;
}
- numSessions--;
- break;
- }
- }
-}
-void Webserver::HttpInterpreter::CheckSessions()
-{
- // Check if any HTTP session can be purged
- const uint32_t now = millis();
- for (int i = numSessions - 1; i >=0 ; i--)
- {
- if (!sessions[i].isPostUploading && (now - sessions[i].lastQueryTime) > httpSessionTimeout)
- {
- for (size_t k = i + 1; k < numSessions; k++)
+ for (size_t k = i + 1; k < numSessions; ++k)
{
memcpy(&sessions[k - 1], &sessions[k], sizeof(HttpSession));
}
numSessions--;
- clientsServed++; // assume the disconnected client hasn't fetched the G-Code reply yet
- }
- }
-
- // If we cannot send the G-Code reply to anyone, we may free up some run-time space by dumping it
- if (numSessions == 0 || clientsServed >= numSessions)
- {
- while (!gcodeReply->IsEmpty())
- {
- OutputBuffer::ReleaseAll(gcodeReply->Pop());
+ return true;
}
- clientsServed = 0;
}
+ return false;
}
// Process a received string of gcodes
@@ -1706,6 +1794,46 @@ void Webserver::HttpInterpreter::HandleGCodeReply(const char *reply)
}
}
+// Called to process a deferred request and takes care of the current Webserver transaction
+void Webserver::HttpInterpreter::ProcessDeferredRequest()
+{
+ OutputBuffer *jsonResponse = nullptr;
+ bool doingDeferredRequest = processingDeferredRequest;
+
+ // At the moment only file info requests are deferred.
+ // Parsing the file may take a while, so keep LwIP running while we're waiting
+ network->Unlock();
+ bool gotFileInfo = reprap.GetPrintMonitor()->GetFileInfoResponse(filenameBeingProcessed, jsonResponse);
+ while (!network->Lock());
+
+ // Because LwIP was unlocked before, there is a chance that the ConnectionLost() call has already
+ // stopped the file parsing. Check this special case
+ NetworkTransaction *transaction = webserver->currentTransaction;
+ if (doingDeferredRequest == processingDeferredRequest)
+ {
+ processingDeferredRequest = !gotFileInfo;
+ if (gotFileInfo)
+ {
+ // Got it - send the response now
+ transaction->Write("HTTP/1.1 200 OK\n");
+ transaction->Write("Cache-Control: no-cache, no-store, must-revalidate\n");
+ transaction->Write("Pragma: no-cache\n");
+ transaction->Write("Expires: 0\n");
+ transaction->Write("Content-Type: application/json\n");
+ transaction->Printf("Content-Length: %u\n", (jsonResponse != nullptr) ? jsonResponse->Length() : 0);
+ transaction->Printf("Connection: close\n\n");
+ transaction->Write(jsonResponse);
+
+ transaction->Commit(false);
+ }
+ else
+ {
+ // File hasn't been fully parsed yet, try again later
+ transaction->Defer(false);
+ }
+ }
+}
+
//********************************************************************************************
//
@@ -1734,7 +1862,7 @@ void Webserver::FtpInterpreter::ConnectionEstablished()
}
// Is this a new connection on the data port?
- NetworkTransaction *transaction = network->GetTransaction();
+ NetworkTransaction *transaction = webserver->currentTransaction;
if (transaction->GetLocalPort() != FTP_PORT)
{
if (state == waitingForPasvPort)
@@ -1742,6 +1870,7 @@ void Webserver::FtpInterpreter::ConnectionEstablished()
// Yes - save it for the main request
network->SaveDataConnection();
state = pasvPortConnected;
+ transaction->Discard();
}
else
{
@@ -1768,27 +1897,27 @@ void Webserver::FtpInterpreter::ConnectionEstablished()
}
}
-void Webserver::FtpInterpreter::ConnectionLost(uint32_t remoteIP, uint16_t remotePort, uint16_t localPort)
+// May be called from ISR!
+void Webserver::FtpInterpreter::ConnectionLost(const ConnectionState *cs)
{
connectedClients--;
- if (localPort != FTP_PORT)
+ if (cs->GetLocalPort() != FTP_PORT)
{
- // Close the data port
- network->CloseDataPort();
-
- // Send response
+ // Did everything work out? Usually this is only called for uploads
if (network->AcquireFTPTransaction())
{
+ webserver->currentTransaction = network->GetTransaction();
if (state == doingPasvIO)
{
- if (uploadState != uploadError)
+ if (uploadState != uploadError && !cs->IsTerminated())
{
SendReply(226, "Transfer complete.");
+ FinishUpload(0);
}
else
{
- SendReply(526, "Upload failed!");
+ SendReply(526, "Transfer failed!");
}
}
else
@@ -1797,15 +1926,13 @@ void Webserver::FtpInterpreter::ConnectionLost(uint32_t remoteIP, uint16_t remot
}
}
- // Do file handling
- if (IsUploading())
- {
- FinishUpload(0);
- uploadState = notUploading;
- }
+ // Close the data port and reset our state again
+ network->CloseDataPort();
+ CancelUpload();
state = authenticated;
}
- else if (connectedClients == 0)
+
+ if (connectedClients == 0)
{
// Last one gone now...
ResetState();
@@ -1871,7 +1998,7 @@ void Webserver::FtpInterpreter::ResetState()
bool Webserver::FtpInterpreter::DoingFastUpload() const
{
- return (IsUploading() && network->GetTransaction()->GetLocalPort() == network->GetDataPort());
+ return (IsUploading() && webserver->currentTransaction->GetLocalPort() == network->GetDataPort());
}
// return true if an error has occurred, false otherwise
@@ -1934,8 +2061,9 @@ void Webserver::FtpInterpreter::ProcessLine()
// get current dir
else if (StringEquals(clientMessage, "PWD"))
{
- snprintf(ftpResponse, ftpResponseLength, "\"%s\"", currentDir);
- SendReply(257, ftpResponse);
+ NetworkTransaction *transaction = webserver->currentTransaction;
+ transaction->Printf("257 \"%s\"\r\n", currentDir);
+ transaction->Commit(true);
}
// set current dir
else if (StringStartsWith(clientMessage, "CWD"))
@@ -1951,7 +2079,7 @@ void Webserver::FtpInterpreter::ProcessLine()
// switch transfer mode (sends response, but doesn't have any effects)
else if (StringStartsWith(clientMessage, "TYPE"))
{
- for(unsigned int i=4; i<clientPointer; i++)
+ for(size_t i = 4; i < clientPointer; i++)
{
if (clientMessage[i] == 'I')
{
@@ -1975,17 +2103,18 @@ void Webserver::FtpInterpreter::ProcessLine()
const byte *ip_address = network->IPAddress();
/* open random port > 1023 */
- rand();
+ //rand(); // TRNG doesn't require this
uint16_t pasv_port = random(1024, 65535);
network->OpenDataPort(pasv_port);
portOpenTime = millis();
state = waitingForPasvPort;
/* send FTP response */
- snprintf(ftpResponse, ftpResponseLength, "Entering Passive Mode (%d,%d,%d,%d,%d,%d)",
+ NetworkTransaction *transaction = webserver->currentTransaction;
+ transaction->Printf("227 Entering Passive Mode (%d,%d,%d,%d,%d,%d)\r\n",
ip_address[0], ip_address[1], ip_address[2], ip_address[3],
pasv_port / 256, pasv_port % 256);
- SendReply(227, ftpResponse);
+ transaction->Commit(true);
}
// PASV commands are not supported in this state
else if (StringEquals(clientMessage, "LIST") || StringStartsWith(clientMessage, "RETR") || StringStartsWith(clientMessage, "STOR"))
@@ -2028,8 +2157,9 @@ void Webserver::FtpInterpreter::ProcessLine()
if (platform->GetMassStorage()->MakeDirectory(location))
{
- snprintf(ftpResponse, ftpResponseLength, "\"%s\" created", location);
- SendReply(257, ftpResponse);
+ NetworkTransaction *transaction = webserver->currentTransaction;
+ transaction->Printf("257 \"%s\" created\r\n", location);
+ transaction->Commit(true);
}
else
{
@@ -2094,7 +2224,7 @@ void Webserver::FtpInterpreter::ProcessLine()
break;
case waitingForPasvPort:
- if (!reprap.Debug(moduleWebserver) && millis() - portOpenTime > ftpPasvPortTimeout)
+ if (millis() - portOpenTime > ftpPasvPortTimeout)
{
SendReply(425, "Failed to establish connection.");
@@ -2103,7 +2233,7 @@ void Webserver::FtpInterpreter::ProcessLine()
}
else
{
- network->WaitForDataConection();
+ webserver->currentTransaction->Defer(true);
}
break;
@@ -2115,33 +2245,25 @@ void Webserver::FtpInterpreter::ProcessLine()
// list directory entries
if (StringEquals(clientMessage, "LIST"))
{
- // send response via main port
- strncpy(ftpResponse, "150 Here comes the directory listing.\r\n", ftpResponseLength);
- NetworkTransaction *transaction = network->GetTransaction();
- transaction->Write(ftpResponse);
- transaction->Commit(true);
-
- // send file list via data port
if (network->AcquireDataTransaction())
{
+ // send announcement via ftp main port
+ SendReply(150, "Here comes the directory listing.");
+
+ // send directory listing via data port
NetworkTransaction *dataTransaction = network->GetTransaction();
FileInfo fileInfo;
if (platform->GetMassStorage()->FindFirst(currentDir, fileInfo))
{
- char line[ftpFileListLineLength];
-
do {
// Example for a typical UNIX-like file list:
// "drwxr-xr-x 2 ftp ftp 0 Apr 11 2013 bin\r\n"
- char dirChar = (fileInfo.isDirectory) ? 'd' : '-';
- const uint8_t month = (fileInfo.month == 0) ? 1 : fileInfo.month; // without this check FileZilla won't display incomplete uploads properly
- snprintf(line, ARRAY_SIZE(line), "%crw-rw-rw- 1 ftp ftp %13lu %s %02d %04d %s\r\n",
+ const char dirChar = (fileInfo.isDirectory) ? 'd' : '-';
+ const uint8_t month = (fileInfo.month == 0) ? 1 : fileInfo.month; // without this check FileZilla won't display incomplete uploads properly
+ dataTransaction->Printf("%crw-rw-rw- 1 ftp ftp %13lu %s %02d %04d %s\r\n",
dirChar, fileInfo.size, platform->GetMassStorage()->GetMonthName(month),
fileInfo.day, fileInfo.year, fileInfo.fileName);
-
- // Fortunately we don't need to bother with output buffer chunks any more...
- dataTransaction->Write(line);
} while (platform->GetMassStorage()->FindNext(fileInfo));
}
@@ -2161,11 +2283,8 @@ void Webserver::FtpInterpreter::ProcessLine()
ReadFilename(4);
FileStore *file = platform->GetFileStore(currentDir, filename, true);
- if (StartUpload(file))
+ if (StartUpload(file, filename))
{
- strncpy(filenameBeingUploaded, filename, ARRAY_SIZE(filenameBeingUploaded));
- filenameBeingUploaded[ARRAY_UPB(filenameBeingUploaded)] = 0;
-
SendReply(150, "OK to send data.");
state = doingPasvIO;
}
@@ -2188,11 +2307,13 @@ void Webserver::FtpInterpreter::ProcessLine()
}
else
{
- snprintf(ftpResponse, ftpResponseLength, "Opening data connection for %s (%lu bytes).", filename, file->Length());
- SendReply(150, ftpResponse);
-
if (network->AcquireDataTransaction())
{
+ // send announcement via main ftp port
+ NetworkTransaction *transaction = webserver->currentTransaction;
+ transaction->Printf("150 Opening data connection for %s (%lu bytes).\r\n", filename, file->Length());
+ transaction->Commit(true);
+
// send the file via data port
NetworkTransaction *dataTransaction = network->GetTransaction();
dataTransaction->SetFileToWrite(file);
@@ -2247,14 +2368,14 @@ void Webserver::FtpInterpreter::ProcessLine()
void Webserver::FtpInterpreter::SendReply(int code, const char *message, bool keepConnection)
{
- NetworkTransaction *transaction = network->GetTransaction();
+ NetworkTransaction *transaction = webserver->currentTransaction;
transaction->Printf("%d %s\r\n", code, message);
transaction->Commit(keepConnection);
}
void Webserver::FtpInterpreter::SendFeatures()
{
- NetworkTransaction *transaction = network->GetTransaction();
+ NetworkTransaction *transaction = webserver->currentTransaction;
transaction->Write("211-Features:\r\n");
transaction->Write("PASV\r\n"); // support PASV mode
transaction->Write("211 End\r\n");
@@ -2413,7 +2534,8 @@ void Webserver::TelnetInterpreter::ConnectionEstablished()
}
}
-void Webserver::TelnetInterpreter::ConnectionLost(uint32_t remoteIP, uint16_t remotePort, uint16_t localPort)
+// May be called from ISR!
+void Webserver::TelnetInterpreter::ConnectionLost(const ConnectionState *cs)
{
connectedClients--;
if (connectedClients == 0)
@@ -2524,7 +2646,7 @@ void Webserver::TelnetInterpreter::ProcessLine()
ProcessGcode(clientMessage);
if (HasDataToSend())
{
- SendGCodeReply(transaction);
+ SendGCodeReply();
}
else
{
@@ -2595,9 +2717,15 @@ char Webserver::TelnetInterpreter::ReadGCode()
// Handle a G-Code reply from the GCodes class; replace \n with \r\n
void Webserver::TelnetInterpreter::HandleGCodeReply(OutputBuffer *reply)
{
- if (reply != nullptr && state >= authenticated && network->AcquireTelnetTransaction())
+ if (reply != nullptr && state >= authenticated)
{
- // We need a valid OutputBuffer to start the conversion
+ if (!network->AcquireTelnetTransaction())
+ {
+ // We must be able to send the response to the client on the next Spin call
+ return;
+ }
+
+ // We need a valid OutputBuffer to start the conversion from NL to CRNL
if (gcodeReply == nullptr)
{
OutputBuffer *buffer;
@@ -2632,16 +2760,22 @@ void Webserver::TelnetInterpreter::HandleGCodeReply(OutputBuffer *reply)
}
else
{
- // Don't use buffers that may never get released...
+ // Don't store buffers that may never get released...
OutputBuffer::ReleaseAll(reply);
}
}
void Webserver::TelnetInterpreter::HandleGCodeReply(const char *reply)
{
- if (reply != nullptr && state >= authenticated && network->AcquireTelnetTransaction())
+ if (reply != nullptr && state >= authenticated)
{
- // We need a valid OutputBuffer to start the conversion
+ if (!network->AcquireTelnetTransaction())
+ {
+ // We must be able to send the response to the client on the next Spin call
+ return;
+ }
+
+ // We need a valid OutputBuffer to start the conversion from NL to CRNL
if (gcodeReply == nullptr)
{
OutputBuffer *buffer;
@@ -2671,12 +2805,13 @@ void Webserver::TelnetInterpreter::HandleGCodeReply(const char *reply)
}
}
-void Webserver::TelnetInterpreter::SendGCodeReply(NetworkTransaction *transaction)
+void Webserver::TelnetInterpreter::SendGCodeReply()
{
+ NetworkTransaction *transaction = webserver->currentTransaction;
transaction->Write(gcodeReply);
- gcodeReply = nullptr;
-
transaction->Commit(true);
+
+ gcodeReply = nullptr;
}
// vim: ts=4:sw=4
diff --git a/src/Webserver.h b/src/Webserver.h
index 0d529c3f..e7adca42 100644
--- a/src/Webserver.h
+++ b/src/Webserver.h
@@ -30,14 +30,16 @@ Licence: GPL
#ifndef WEBSERVER_H
#define WEBSERVER_H
-const uint16_t gcodeBufferLength = 512; // size of our gcode ring buffer, preferably a power of 2
+/* Generic values */
+
+const size_t gcodeBufferLength = 512; // size of our gcode ring buffer, preferably a power of 2
+const uint32_t processTimeout = 4000; // how long a connection can block the webserver (in ms)
/* HTTP */
#define KO_START "rr_"
#define KO_FIRST 3
-const uint16_t webUploadBufferSize = 2300; // maximum size of HTTP GET upload packets (webMessageLength - 700)
const uint16_t webMessageLength = 3000; // maximum length of the web message we accept after decoding
const size_t minHttpResponseSize = 768; // minimum number of bytes required for an HTTP response
@@ -50,8 +52,6 @@ const uint32_t httpSessionTimeout = 8000; // HTTP session timeout in millisecon
/* FTP */
-const uint16_t ftpResponseLength = 128; // maximum FTP response length
-const uint16_t ftpFileListLineLength = 256; // maximum length for one FTP file listing line
const uint16_t ftpMessageLength = 128; // maximum line length for incoming FTP commands
const uint32_t ftpPasvPortTimeout = 10000; // maximum time to wait for an FTP data connection in milliseconds
@@ -78,16 +78,18 @@ class ProtocolInterpreter
ProtocolInterpreter(Platform *p, Webserver *ws, Network *n);
virtual ~ProtocolInterpreter() { } // to keep Eclipse happy
+ virtual void Diagnostics() = 0;
+ virtual void Spin();
- virtual void ConnectionEstablished() { }
- virtual void ConnectionLost(uint32_t remoteIP, uint16_t remotePort, uint16_t localPort) { }
+ virtual void ConnectionEstablished();
+ virtual void ConnectionLost(const ConnectionState *cs) { }
virtual bool CharFromClient(const char c) = 0;
virtual void ResetState() = 0;
virtual bool NeedMoreData();
virtual bool DoingFastUpload() const;
- virtual void DoFastUpload(NetworkTransaction *transaction);
- virtual void CancelUpload();
+ virtual void DoFastUpload();
+ void CancelUpload(); // may be called by ISR!
protected:
@@ -103,13 +105,13 @@ class ProtocolInterpreter
uploadError // upload in progress but had error
};
- UploadState uploadState;
+ volatile UploadState uploadState;
FileData fileBeingUploaded;
char filenameBeingUploaded[FILENAME_LENGTH];
- virtual bool StartUpload(FileStore *file);
+ bool StartUpload(FileStore *file, const char *fileName);
bool IsUploading() const;
- virtual void FinishUpload(uint32_t fileLength);
+ bool FinishUpload(uint32_t fileLength);
};
class Webserver
@@ -117,6 +119,7 @@ class Webserver
public:
friend class Platform;
+ friend class ProtocolInterpreter;
Webserver(Platform* p, Network *n);
void Init();
@@ -143,18 +146,16 @@ class Webserver
public:
HttpInterpreter(Platform *p, Webserver *ws, Network *n);
+ void Spin();
void Diagnostics();
- void ConnectionLost(uint32_t remoteIP, uint16_t remotePort, uint16_t localPort) override;
+ void ConnectionLost(const ConnectionState *cs);
bool CharFromClient(const char c) override;
void ResetState() override;
+ void ResetSessions();
bool NeedMoreData() override;
bool DoingFastUpload() const override;
- void DoFastUpload(NetworkTransaction *transaction) override;
- void CancelUpload() override;
-
- void ResetSessions();
- void CheckSessions();
+ void DoFastUpload();
bool GCodeAvailable() const;
char ReadGCode();
@@ -185,7 +186,7 @@ class Webserver
doingHeaderValue, // receiving a header value
doingHeaderContinuation // received a newline after a header value
};
- HttpState state;
+ volatile HttpState state;
struct KeyValueIndices
{
@@ -194,11 +195,10 @@ class Webserver
};
void SendFile(const char* nameOfFileToSend);
- void SendConfigFile(NetworkTransaction *transaction);
- void SendGCodeReply(NetworkTransaction *transaction);
+ void SendConfigFile();
+ void SendGCodeReply();
void SendJsonResponse(const char* command);
bool GetJsonResponse(const char* request, OutputBuffer *&response, const char* key, const char* value, size_t valueLength, bool& keepOpen);
- void GetJsonUploadResponse(OutputBuffer *response);
bool ProcessMessage();
bool RejectMessage(const char* s, unsigned int code = 500);
@@ -224,12 +224,13 @@ class Webserver
};
HttpSession sessions[maxHttpSessions];
- size_t numSessions, clientsServed;
+ volatile uint8_t numSessions;
+ uint8_t clientsServed;
bool Authenticate();
bool IsAuthenticated() const;
void UpdateAuthentication();
- void RemoveAuthentication();
+ bool RemoveAuthentication();
// Deal with incoming G-Codes
@@ -241,13 +242,19 @@ class Webserver
void ProcessGcode(const char* gc);
void StoreGcodeData(const char* data, uint16_t len);
- // Response from GCodes class
+ // Responses from GCodes class
OutputStack *gcodeReply;
- protected:
- bool processingDeferredRequest; // it's no good idea to parse 128kB of text in one go...
- uint32_t postFileLength, uploadedBytes; // how many POST bytes do we expect and how many have already been written?
+ // File uploads
+ uint32_t postFileLength, uploadedBytes; // How many POST bytes do we expect and how many have already been written?
+
+ // Deferred requests (rr_fileinfo)
+ volatile bool processingDeferredRequest; // Are we processing a transaction multiple times to retrieve information?
+ ConnectionState *deferredRequestConnection; // Which connection expects a response?
+ char filenameBeingProcessed[FILENAME_LENGTH]; // The filename being processed (for rr_fileinfo)
+
+ void ProcessDeferredRequest();
};
HttpInterpreter *httpInterpreter;
@@ -258,7 +265,7 @@ class Webserver
FtpInterpreter(Platform *p, Webserver *ws, Network *n);
void Diagnostics();
void ConnectionEstablished() override;
- void ConnectionLost(uint32_t remoteIP, uint16_t remotePort, uint16_t localPort) override;
+ void ConnectionLost(const ConnectionState *cs) override;
bool CharFromClient(const char c) override;
void ResetState() override;
@@ -275,12 +282,11 @@ class Webserver
pasvPortConnected, // client connected to PASV port, ready to send data
doingPasvIO // client is connected and data is being transferred
};
- FtpState state;
- uint8_t connectedClients;
+ volatile FtpState state;
+ volatile uint8_t connectedClients;
char clientMessage[ftpMessageLength];
unsigned int clientPointer;
- char ftpResponse[ftpResponseLength];
char filename[FILENAME_LENGTH];
char currentDir[FILENAME_LENGTH];
@@ -303,7 +309,7 @@ class Webserver
TelnetInterpreter(Platform *p, Webserver *ws, Network *n);
void Diagnostics();
void ConnectionEstablished() override;
- void ConnectionLost(uint32_t remoteIP, uint16_t remotePort, uint16_t local_port) override;
+ void ConnectionLost(const ConnectionState *cs) override;
bool CharFromClient(const char c) override;
void ResetState() override;
bool NeedMoreData() override;
@@ -315,7 +321,7 @@ class Webserver
uint16_t GetGCodeBufferSpace() const;
bool HasDataToSend() const;
- void SendGCodeReply(NetworkTransaction *transaction);
+ void SendGCodeReply();
private:
@@ -326,8 +332,8 @@ class Webserver
authenticating, // not logged in
authenticated // logged in
};
- TelnetState state;
- uint8_t connectedClients;
+ volatile TelnetState state;
+ volatile uint8_t connectedClients;
uint32_t connectTime;
char clientMessage[telnetMessageLength];
@@ -354,7 +360,9 @@ class Webserver
Platform* platform;
Network* network;
bool webserverActive;
- const ConnectionState *readingConnection;
+ ConnectionState * volatile readingConnection;
+ uint32_t readingConnectionTimestamp;
+ NetworkTransaction *currentTransaction;
float longWait;
};