diff options
72 files changed, 1162 insertions, 1234 deletions
@@ -4,7 +4,7 @@ <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="Duet085"> <macros> - <stringMacro name="LinkFlags2" type="VALUE_TEXT" value="-Wl,--end-group -lm -gcc"/> + <stringMacro name="LinkFlags2" type="VALUE_TEXT" value="-Wl,--end-group -lm"/> <stringMacro name="LinkFlags1" type="VALUE_TEXT" 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"/> <stringMacro name="CoreName" type="VALUE_TEXT" value="CoreNG"/> <stringMacro name="GccPath" type="VALUE_TEXT" value="C:\Program Files (x86)\GNU Tools ARM Embedded\6 2017-q2-update\bin"/> @@ -117,9 +117,9 @@ <storageModule moduleId="org.eclipse.cdt.core.externalSettings"/> </cconfiguration> <cconfiguration id="cdt.managedbuild.config.gnu.cross.exe.release.516195201.976458850.241502451"> - <storageModule buildSystemId="org.eclipse.cdt.managedbuilder.core.configurationDataProvider" id="cdt.managedbuild.config.gnu.cross.exe.release.516195201.976458850.241502451" moduleId="org.eclipse.cdt.core.settings" name="DuetWiFi"> + <storageModule buildSystemId="org.eclipse.cdt.managedbuilder.core.configurationDataProvider" id="cdt.managedbuild.config.gnu.cross.exe.release.516195201.976458850.241502451" moduleId="org.eclipse.cdt.core.settings" name="Duet2"> <macros> - <stringMacro name="LinkFlags2" type="VALUE_TEXT" value="-Wl,--end-group -lm -gcc"/> + <stringMacro name="LinkFlags2" type="VALUE_TEXT" value="-Wl,--end-group -lm"/> <stringMacro name="LinkFlags1" type="VALUE_TEXT" 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"/> <stringMacro name="CoreName" type="VALUE_TEXT" value="CoreNG"/> <stringMacro name="GccPath" type="VALUE_TEXT" value="C:\Program Files (x86)\GNU Tools ARM Embedded\6 2017-q2-update\bin"/> @@ -135,7 +135,7 @@ </extensions> </storageModule> <storageModule moduleId="cdtBuildSystem" version="4.0.0"> - <configuration artifactExtension="elf" artifactName="DuetWiFiFirmware" buildArtefactType="org.eclipse.cdt.build.core.buildArtefactType.exe" buildProperties="org.eclipse.cdt.build.core.buildArtefactType=org.eclipse.cdt.build.core.buildArtefactType.exe,org.eclipse.cdt.build.core.buildType=org.eclipse.cdt.build.core.buildType.release" cleanCommand="rm -rf" description="" id="cdt.managedbuild.config.gnu.cross.exe.release.516195201.976458850.241502451" name="DuetWiFi" parent="cdt.managedbuild.config.gnu.cross.exe.release" postannouncebuildStep="Generating binary file" postbuildStep="arm-none-eabi-objcopy -O binary ${workspace_loc:/${ProjName}/${ConfigName}}/DuetWiFiFirmware.elf ${workspace_loc:/${ProjName}/${ConfigName}}/DuetWiFiFirmware.bin"> + <configuration artifactExtension="elf" artifactName="Duet2CombinedFirmware" buildArtefactType="org.eclipse.cdt.build.core.buildArtefactType.exe" buildProperties="org.eclipse.cdt.build.core.buildArtefactType=org.eclipse.cdt.build.core.buildArtefactType.exe,org.eclipse.cdt.build.core.buildType=org.eclipse.cdt.build.core.buildType.release" cleanCommand="rm -rf" description="" id="cdt.managedbuild.config.gnu.cross.exe.release.516195201.976458850.241502451" name="Duet2" parent="cdt.managedbuild.config.gnu.cross.exe.release" postannouncebuildStep="Generating binary file" postbuildStep="arm-none-eabi-objcopy -O binary ${workspace_loc:/${ProjName}/${ConfigName}}/Duet2CombinedFirmware.elf ${workspace_loc:/${ProjName}/${ConfigName}}/Duet2CombinedFirmware.bin"> <folderInfo id="cdt.managedbuild.config.gnu.cross.exe.release.516195201.976458850.241502451." name="/" resourcePath=""> <toolChain id="cdt.managedbuild.toolchain.gnu.cross.exe.release.1362047835" name="Cross GCC" superClass="cdt.managedbuild.toolchain.gnu.cross.exe.release"> <option id="cdt.managedbuild.option.gnu.cross.path.1491883811" name="Path" superClass="cdt.managedbuild.option.gnu.cross.path" useByScannerDiscovery="false" value="${GccPath}" valueType="string"/> @@ -234,7 +234,7 @@ <cconfiguration id="cdt.managedbuild.config.gnu.cross.exe.release.516195201.976458850.1027429289"> <storageModule buildSystemId="org.eclipse.cdt.managedbuilder.core.configurationDataProvider" id="cdt.managedbuild.config.gnu.cross.exe.release.516195201.976458850.1027429289" moduleId="org.eclipse.cdt.core.settings" name="RADDS"> <macros> - <stringMacro name="LinkFlags2" type="VALUE_TEXT" value="-Wl,--end-group -lm -gcc"/> + <stringMacro name="LinkFlags2" type="VALUE_TEXT" value="-Wl,--end-group -lm"/> <stringMacro name="LinkFlags1" type="VALUE_TEXT" 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"/> <stringMacro name="CoreName" type="VALUE_TEXT" value="CoreNG"/> <stringMacro name="GccPath" type="VALUE_TEXT" value="C:\Program Files (x86)\GNU Tools ARM Embedded\6 2017-q2-update\bin"/> @@ -341,132 +341,10 @@ </storageModule> <storageModule moduleId="org.eclipse.cdt.core.externalSettings"/> </cconfiguration> - <cconfiguration id="cdt.managedbuild.config.gnu.cross.exe.release.516195201.976458850.241502451.1275216290"> - <storageModule buildSystemId="org.eclipse.cdt.managedbuilder.core.configurationDataProvider" id="cdt.managedbuild.config.gnu.cross.exe.release.516195201.976458850.241502451.1275216290" moduleId="org.eclipse.cdt.core.settings" name="DuetEthernet"> - <macros> - <stringMacro name="LinkFlags2" type="VALUE_TEXT" value="-Wl,--end-group -lm -gcc"/> - <stringMacro name="LinkFlags1" type="VALUE_TEXT" 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"/> - <stringMacro name="CoreName" type="VALUE_TEXT" value="CoreNG"/> - <stringMacro name="GccPath" type="VALUE_TEXT" value="C:\Program Files (x86)\GNU Tools ARM Embedded\6 2017-q2-update\bin"/> - </macros> - <externalSettings/> - <extensions> - <extension id="org.eclipse.cdt.core.ELF" point="org.eclipse.cdt.core.BinaryParser"/> - <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"/> - </extensions> - </storageModule> - <storageModule moduleId="cdtBuildSystem" version="4.0.0"> - <configuration artifactExtension="elf" artifactName="DuetEthernetFirmware" buildArtefactType="org.eclipse.cdt.build.core.buildArtefactType.exe" buildProperties="org.eclipse.cdt.build.core.buildArtefactType=org.eclipse.cdt.build.core.buildArtefactType.exe,org.eclipse.cdt.build.core.buildType=org.eclipse.cdt.build.core.buildType.release" cleanCommand="rm -rf" description="" id="cdt.managedbuild.config.gnu.cross.exe.release.516195201.976458850.241502451.1275216290" name="DuetEthernet" parent="cdt.managedbuild.config.gnu.cross.exe.release" postannouncebuildStep="Generating binary file" postbuildStep="arm-none-eabi-objcopy -O binary ${workspace_loc:/${ProjName}/${ConfigName}}/DuetEthernetFirmware.elf ${workspace_loc:/${ProjName}/${ConfigName}}/DuetEthernetFirmware.bin"> - <folderInfo id="cdt.managedbuild.config.gnu.cross.exe.release.516195201.976458850.241502451.1275216290." name="/" resourcePath=""> - <toolChain id="cdt.managedbuild.toolchain.gnu.cross.exe.release.311889538" name="Cross GCC" superClass="cdt.managedbuild.toolchain.gnu.cross.exe.release"> - <option id="cdt.managedbuild.option.gnu.cross.path.1965306885" name="Path" superClass="cdt.managedbuild.option.gnu.cross.path" useByScannerDiscovery="false" value="${GccPath}" valueType="string"/> - <option id="cdt.managedbuild.option.gnu.cross.prefix.444696517" name="Prefix" superClass="cdt.managedbuild.option.gnu.cross.prefix" useByScannerDiscovery="false" value="arm-none-eabi-" valueType="string"/> - <targetPlatform archList="all" binaryParser="org.eclipse.cdt.core.ELF" id="cdt.managedbuild.targetPlatform.gnu.cross.252007317" isAbstract="false" osList="all" superClass="cdt.managedbuild.targetPlatform.gnu.cross"/> - <builder buildPath="${workspace_loc:/RepRapFirmware}/Release" id="cdt.managedbuild.builder.gnu.cross.310136248" keepEnvironmentInBuildfile="false" managedBuildOn="true" name="Gnu Make Builder" parallelBuildOn="true" parallelizationNumber="optimal" superClass="cdt.managedbuild.builder.gnu.cross"/> - <tool id="cdt.managedbuild.tool.gnu.cross.assembler.2020291169" name="Cross GCC Assembler" superClass="cdt.managedbuild.tool.gnu.cross.assembler"> - <inputType id="cdt.managedbuild.tool.gnu.assembler.input.1429050288" 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.1431507147" 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.1104471278" name="Optimization Level" superClass="gnu.c.compiler.option.optimization.level" useByScannerDiscovery="false" value="gnu.c.optimization.level.more" valueType="enumerated"/> - <option id="gnu.c.compiler.option.debugging.level.477980593" name="Debug Level" superClass="gnu.c.compiler.option.debugging.level" useByScannerDiscovery="false" value="gnu.c.debugging.level.none" valueType="enumerated"/> - <option id="gnu.c.compiler.option.misc.verbose.1592038422" name="Verbose (-v)" superClass="gnu.c.compiler.option.misc.verbose" useByScannerDiscovery="false" value="false" valueType="boolean"/> - <option id="gnu.c.compiler.option.misc.other.370908347" name="Other flags" superClass="gnu.c.compiler.option.misc.other" useByScannerDiscovery="false" value="-c -std=gnu99 -mcpu=cortex-m4 -mthumb -mfpu=fpv4-sp-d16 -mfloat-abi=hard -ffunction-sections -fdata-sections -nostdlib -Wdouble-promotion -fsingle-precision-constant "-Wa,-ahl=$*.s"" valueType="string"/> - <option id="gnu.c.compiler.option.include.paths.1126811520" name="Include paths (-I)" superClass="gnu.c.compiler.option.include.paths" useByScannerDiscovery="false" valueType="includePath"> - <listOptionValue builtIn="false" value=""${workspace_loc:/${CoreName}/cores/arduino}""/> - <listOptionValue builtIn="false" value=""${workspace_loc:/${CoreName}/libraries/Storage}""/> - <listOptionValue builtIn="false" value=""${workspace_loc:/${CoreName}/asf}""/> - <listOptionValue builtIn="false" value=""${workspace_loc:/${CoreName}/asf/common/utils}""/> - <listOptionValue builtIn="false" value=""${workspace_loc:/${CoreName}/asf/common/services/ioport}""/> - <listOptionValue builtIn="false" value=""${workspace_loc:/${CoreName}/asf/sam/drivers/hsmci}""/> - <listOptionValue builtIn="false" value=""${workspace_loc:/${CoreName}/asf/sam/drivers/rstc}""/> - <listOptionValue builtIn="false" value=""${workspace_loc:/${CoreName}/asf/sam/drivers/rtc}""/> - <listOptionValue builtIn="false" value=""${workspace_loc:/${CoreName}/asf/sam/utils}""/> - <listOptionValue builtIn="false" value=""${workspace_loc:/${CoreName}/asf/sam/utils/cmsis/sam4e/include}""/> - <listOptionValue builtIn="false" value=""${workspace_loc:/${CoreName}/asf/sam/utils/header_files}""/> - <listOptionValue builtIn="false" value=""${workspace_loc:/${CoreName}/asf/sam/utils/preprocessor}""/> - <listOptionValue builtIn="false" value=""${workspace_loc:/${CoreName}/asf/thirdparty/CMSIS/Include}""/> - <listOptionValue builtIn="false" value=""${workspace_loc:/${CoreName}/variants/duetNG}""/> - <listOptionValue builtIn="false" value=""${workspace_loc:/${ProjName}/src/Networking}""/> - <listOptionValue builtIn="false" value=""${workspace_loc:/${ProjName}/src/Networking/W5500Ethernet}""/> - <listOptionValue builtIn="false" value=""${workspace_loc:/${ProjName}/src/Networking/W5500Ethernet/Wiznet/Ethernet}""/> - </option> - <option id="gnu.c.compiler.option.preprocessor.def.symbols.299877277" name="Defined symbols (-D)" superClass="gnu.c.compiler.option.preprocessor.def.symbols" useByScannerDiscovery="false" valueType="definedSymbols"> - <listOptionValue builtIn="false" value="__SAM4E8E__"/> - <listOptionValue builtIn="false" value="DUET_NG"/> - </option> - <inputType id="cdt.managedbuild.tool.gnu.c.compiler.input.786131774" superClass="cdt.managedbuild.tool.gnu.c.compiler.input"/> - </tool> - <tool id="cdt.managedbuild.tool.gnu.cross.c.linker.212863977" name="Cross GCC Linker" superClass="cdt.managedbuild.tool.gnu.cross.c.linker"/> - <tool id="cdt.managedbuild.tool.gnu.cross.archiver.136873036" name="Cross GCC Archiver" superClass="cdt.managedbuild.tool.gnu.cross.archiver"/> - <tool command="gcc" commandLinePattern="${COMMAND} ${FLAGS} ${OUTPUT_FLAG} ${OUTPUT_PREFIX}${OUTPUT} ${LinkFlags1} "${workspace_loc}/${CoreName}/SAM4E8E/cores/arduino/syscalls.o" ${INPUTS} ${LinkFlags2}" id="cdt.managedbuild.tool.gnu.cross.cpp.linker.394147701" name="Cross G++ Linker" superClass="cdt.managedbuild.tool.gnu.cross.cpp.linker"> - <option id="gnu.cpp.link.option.nostdlibs.278980629" name="No startup or default libs (-nostdlib)" superClass="gnu.cpp.link.option.nostdlibs" useByScannerDiscovery="false" value="false" valueType="boolean"/> - <option id="gnu.cpp.link.option.paths.1667456082" name="Library search path (-L)" superClass="gnu.cpp.link.option.paths" useByScannerDiscovery="false" valueType="libPaths"> - <listOptionValue builtIn="false" value=""${workspace_loc:/${CoreName}/SAM4E8E/}""/> - </option> - <option id="gnu.cpp.link.option.libs.1989128214" name="Libraries (-l)" superClass="gnu.cpp.link.option.libs" useByScannerDiscovery="false" valueType="libs"> - <listOptionValue builtIn="false" value="${CoreName}"/> - </option> - <option id="gnu.cpp.link.option.flags.1163940548" name="Linker flags" superClass="gnu.cpp.link.option.flags" useByScannerDiscovery="false" value="-Os -Wl,--gc-sections -Wl,--fatal-warnings -mcpu=cortex-m4 -mfpu=fpv4-sp-d16 -mfloat-abi=hard -T${workspace_loc:/${CoreName}/variants/duetNG/linker_scripts/gcc/flash.ld} -Wl,-Map,${workspace_loc:/${ProjName}/${ConfigName}}/${BuildArtifactFileBaseName}.map" valueType="string"/> - <inputType id="cdt.managedbuild.tool.gnu.cpp.linker.input.1312104716" 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.1806370384" name="Cross G++ Compiler" superClass="cdt.managedbuild.tool.gnu.cross.cpp.compiler"> - <option id="gnu.cpp.compiler.option.optimization.level.2020978856" name="Optimization Level" superClass="gnu.cpp.compiler.option.optimization.level" useByScannerDiscovery="false" value="gnu.cpp.compiler.optimization.level.more" valueType="enumerated"/> - <option id="gnu.cpp.compiler.option.debugging.level.910542376" name="Debug Level" superClass="gnu.cpp.compiler.option.debugging.level" useByScannerDiscovery="false" value="gnu.cpp.compiler.debugging.level.none" valueType="enumerated"/> - <option id="gnu.cpp.compiler.option.other.verbose.1078412916" name="Verbose (-v)" superClass="gnu.cpp.compiler.option.other.verbose" useByScannerDiscovery="false" value="false" valueType="boolean"/> - <option id="gnu.cpp.compiler.option.other.other.683644273" name="Other flags" superClass="gnu.cpp.compiler.option.other.other" useByScannerDiscovery="false" value="-c -std=gnu++14 -mcpu=cortex-m4 -mthumb -mfpu=fpv4-sp-d16 -mfloat-abi=hard -ffunction-sections -fdata-sections -fno-threadsafe-statics -fno-rtti -fno-exceptions -nostdlib -Wdouble-promotion -fsingle-precision-constant "-Wa,-ahl=$*.s"" valueType="string"/> - <option id="gnu.cpp.compiler.option.include.paths.1135603629" name="Include paths (-I)" superClass="gnu.cpp.compiler.option.include.paths" useByScannerDiscovery="false" valueType="includePath"> - <listOptionValue builtIn="false" value=""${workspace_loc:/${CoreName}/cores/arduino}""/> - <listOptionValue builtIn="false" value=""${workspace_loc:/${CoreName}/libraries/Flash}""/> - <listOptionValue builtIn="false" value=""${workspace_loc:/${CoreName}/libraries/SharedSpi}""/> - <listOptionValue builtIn="false" value=""${workspace_loc:/${CoreName}/libraries/Storage}""/> - <listOptionValue builtIn="false" value=""${workspace_loc:/${CoreName}/libraries/Wire}""/> - <listOptionValue builtIn="false" value=""${workspace_loc:/${CoreName}/asf}""/> - <listOptionValue builtIn="false" value=""${workspace_loc:/${CoreName}/asf/common/utils}""/> - <listOptionValue builtIn="false" value=""${workspace_loc:/${CoreName}/asf/common/services/clock}""/> - <listOptionValue builtIn="false" value=""${workspace_loc:/${CoreName}/asf/common/services/ioport}""/> - <listOptionValue builtIn="false" value=""${workspace_loc:/${CoreName}/asf/sam/drivers}""/> - <listOptionValue builtIn="false" value=""${workspace_loc:/${CoreName}/asf/sam/services/flash_efc}""/> - <listOptionValue builtIn="false" value=""${workspace_loc:/${CoreName}/asf/sam/utils}""/> - <listOptionValue builtIn="false" value=""${workspace_loc:/${CoreName}/asf/sam/utils/cmsis/sam4e/include}""/> - <listOptionValue builtIn="false" value=""${workspace_loc:/${CoreName}/asf/sam/utils/header_files}""/> - <listOptionValue builtIn="false" value=""${workspace_loc:/${CoreName}/asf/sam/utils/preprocessor}""/> - <listOptionValue builtIn="false" value=""${workspace_loc:/${CoreName}/asf/thirdparty/CMSIS/Include}""/> - <listOptionValue builtIn="false" value=""${workspace_loc:/${CoreName}/variants/duetNG}""/> - <listOptionValue builtIn="false" value=""${workspace_loc:/${ProjName}/src}""/> - <listOptionValue builtIn="false" value=""${workspace_loc:/${ProjName}/src/DuetNG}""/> - <listOptionValue builtIn="false" value=""${workspace_loc:/${ProjName}/src/Networking}""/> - <listOptionValue builtIn="false" value=""${workspace_loc:/${ProjName}/src/Networking/W5500Ethernet}""/> - <listOptionValue builtIn="false" value=""${workspace_loc:/${ProjName}/src/Networking/W5500Ethernet/Wiznet/Ethernet}""/> - <listOptionValue builtIn="false" value=""${workspace_loc:/DuetWiFiSocketServer/src/include}""/> - </option> - <option id="gnu.cpp.compiler.option.preprocessor.def.1120095540" name="Defined symbols (-D)" superClass="gnu.cpp.compiler.option.preprocessor.def" useByScannerDiscovery="false" valueType="definedSymbols"> - <listOptionValue builtIn="false" value="__SAM4E8E__"/> - <listOptionValue builtIn="false" value="DUET_NG"/> - <listOptionValue builtIn="false" value="DUET_ETHERNET"/> - <listOptionValue builtIn="false" value="_XOPEN_SOURCE"/> - </option> - <inputType id="cdt.managedbuild.tool.gnu.cpp.compiler.input.2135034744" superClass="cdt.managedbuild.tool.gnu.cpp.compiler.input"/> - </tool> - </toolChain> - </folderInfo> - <sourceEntries> - <entry excluding="src/Networking/ESP8266WiFi|src/Networking/LwipEthernet|src/Alligator|src/SAME70_TEST|src/Display|src/Duet|src/DuetM|src/RADDS" flags="VALUE_WORKSPACE_PATH|RESOLVED" kind="sourcePath" name=""/> - </sourceEntries> - </configuration> - </storageModule> - <storageModule moduleId="org.eclipse.cdt.core.externalSettings"/> - </cconfiguration> <cconfiguration id="cdt.managedbuild.config.gnu.cross.exe.release.516195201.976458850.1745168887"> <storageModule buildSystemId="org.eclipse.cdt.managedbuilder.core.configurationDataProvider" id="cdt.managedbuild.config.gnu.cross.exe.release.516195201.976458850.1745168887" moduleId="org.eclipse.cdt.core.settings" name="Alligator"> <macros> - <stringMacro name="LinkFlags2" type="VALUE_TEXT" value="-Wl,--end-group -lm -gcc"/> + <stringMacro name="LinkFlags2" type="VALUE_TEXT" value="-Wl,--end-group -lm"/> <stringMacro name="LinkFlags1" type="VALUE_TEXT" 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"/> <stringMacro name="CoreName" type="VALUE_TEXT" value="CoreNG"/> <stringMacro name="GccPath" type="VALUE_TEXT" value="C:\Program Files (x86)\GNU Tools ARM Embedded\6 2017-q2-update\bin"/> @@ -587,7 +465,7 @@ <cconfiguration id="cdt.managedbuild.config.gnu.cross.exe.release.516195201.976458850.241502451.1275216290.1979117592"> <storageModule buildSystemId="org.eclipse.cdt.managedbuilder.core.configurationDataProvider" id="cdt.managedbuild.config.gnu.cross.exe.release.516195201.976458850.241502451.1275216290.1979117592" moduleId="org.eclipse.cdt.core.settings" name="DuetM"> <macros> - <stringMacro name="LinkFlags2" type="VALUE_TEXT" value="-Wl,--end-group -lm -gcc"/> + <stringMacro name="LinkFlags2" type="VALUE_TEXT" value="-Wl,--end-group -lm"/> <stringMacro name="LinkFlags1" type="VALUE_TEXT" 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"/> <stringMacro name="CoreName" type="VALUE_TEXT" value="CoreNG"/> <stringMacro name="GccPath" type="VALUE_TEXT" value="C:\Program Files (x86)\GNU Tools ARM Embedded\6 2017-q2-update\bin"/> @@ -706,7 +584,7 @@ <cconfiguration id="cdt.managedbuild.config.gnu.cross.exe.release.516195201.976458850.241502451.1275216290.274082366.1645191116"> <storageModule buildSystemId="org.eclipse.cdt.managedbuilder.core.configurationDataProvider" id="cdt.managedbuild.config.gnu.cross.exe.release.516195201.976458850.241502451.1275216290.274082366.1645191116" moduleId="org.eclipse.cdt.core.settings" name="SAME70"> <macros> - <stringMacro name="LinkFlags2" type="VALUE_TEXT" value="-Wl,--end-group -lm -gcc"/> + <stringMacro name="LinkFlags2" type="VALUE_TEXT" value="-Wl,--end-group -lm"/> <stringMacro name="LinkFlags1" type="VALUE_TEXT" 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"/> <stringMacro name="CoreName" type="VALUE_TEXT" value="CoreNG"/> <stringMacro name="GccPath" type="VALUE_TEXT" value="C:\Program Files (x86)\GNU Tools ARM Embedded\6 2017-q2-update\bin"/> @@ -838,11 +716,10 @@ <storageModule moduleId="org.eclipse.cdt.core.LanguageSettingsProviders"/> <storageModule moduleId="refreshScope" versionNumber="2"> <configuration configurationName="Alligator"/> - <configuration configurationName="DuetEthernet"/> <configuration configurationName="SAME70"/> <configuration configurationName="RADDS"/> + <configuration configurationName="Duet2"/> <configuration configurationName="DuetM"/> - <configuration configurationName="DuetWiFi"/> <configuration configurationName="Duet085"/> </storageModule> <storageModule moduleId="org.eclipse.cdt.internal.ui.text.commentOwnerProjectMappings"/> diff --git a/.settings/language.settings.xml b/.settings/language.settings.xml index 978b6f42..a8f44d89 100644 --- a/.settings/language.settings.xml +++ b/.settings/language.settings.xml @@ -5,18 +5,18 @@ <provider copy-of="extension" id="org.eclipse.cdt.ui.UserLanguageSettingsProvider"/> <provider-reference id="org.eclipse.cdt.core.ReferencedProjectsLanguageSettingsProvider" ref="shared-provider"/> <provider-reference id="org.eclipse.cdt.managedbuilder.core.MBSLanguageSettingsProvider" ref="shared-provider"/> - <provider class="org.eclipse.cdt.internal.build.crossgcc.CrossGCCBuiltinSpecsDetector" console="false" env-hash="-1419419586637520295" id="org.eclipse.cdt.build.crossgcc.CrossGCCBuiltinSpecsDetector" keep-relative-paths="false" name="CDT Cross GCC Built-in Compiler Settings" parameter="${COMMAND} ${FLAGS} -E -P -v -dD "${INPUTS}"" prefer-non-shared="true"> + <provider class="org.eclipse.cdt.internal.build.crossgcc.CrossGCCBuiltinSpecsDetector" console="false" env-hash="1189573167678144698" id="org.eclipse.cdt.build.crossgcc.CrossGCCBuiltinSpecsDetector" keep-relative-paths="false" name="CDT Cross GCC Built-in Compiler Settings" parameter="${COMMAND} ${FLAGS} -E -P -v -dD "${INPUTS}"" prefer-non-shared="true"> <language-scope id="org.eclipse.cdt.core.gcc"/> <language-scope id="org.eclipse.cdt.core.g++"/> </provider> </extension> </configuration> - <configuration id="cdt.managedbuild.config.gnu.cross.exe.release.516195201.976458850.241502451" name="DuetWiFi"> + <configuration id="cdt.managedbuild.config.gnu.cross.exe.release.516195201.976458850.241502451" name="Duet2"> <extension point="org.eclipse.cdt.core.LanguageSettingsProvider"> <provider copy-of="extension" id="org.eclipse.cdt.ui.UserLanguageSettingsProvider"/> <provider-reference id="org.eclipse.cdt.core.ReferencedProjectsLanguageSettingsProvider" ref="shared-provider"/> <provider-reference id="org.eclipse.cdt.managedbuilder.core.MBSLanguageSettingsProvider" ref="shared-provider"/> - <provider class="org.eclipse.cdt.internal.build.crossgcc.CrossGCCBuiltinSpecsDetector" console="false" env-hash="-1419419586637520295" id="org.eclipse.cdt.build.crossgcc.CrossGCCBuiltinSpecsDetector" keep-relative-paths="false" name="CDT Cross GCC Built-in Compiler Settings" parameter="${COMMAND} ${FLAGS} -E -P -v -dD "${INPUTS}"" prefer-non-shared="true"> + <provider class="org.eclipse.cdt.internal.build.crossgcc.CrossGCCBuiltinSpecsDetector" console="false" env-hash="1189573167678144698" id="org.eclipse.cdt.build.crossgcc.CrossGCCBuiltinSpecsDetector" keep-relative-paths="false" name="CDT Cross GCC Built-in Compiler Settings" parameter="${COMMAND} ${FLAGS} -E -P -v -dD "${INPUTS}"" prefer-non-shared="true"> <language-scope id="org.eclipse.cdt.core.gcc"/> <language-scope id="org.eclipse.cdt.core.g++"/> </provider> @@ -27,18 +27,7 @@ <provider copy-of="extension" id="org.eclipse.cdt.ui.UserLanguageSettingsProvider"/> <provider-reference id="org.eclipse.cdt.core.ReferencedProjectsLanguageSettingsProvider" ref="shared-provider"/> <provider-reference id="org.eclipse.cdt.managedbuilder.core.MBSLanguageSettingsProvider" ref="shared-provider"/> - <provider class="org.eclipse.cdt.internal.build.crossgcc.CrossGCCBuiltinSpecsDetector" console="false" env-hash="-1419419586637520295" id="org.eclipse.cdt.build.crossgcc.CrossGCCBuiltinSpecsDetector" keep-relative-paths="false" name="CDT Cross GCC Built-in Compiler Settings" parameter="${COMMAND} ${FLAGS} -E -P -v -dD "${INPUTS}"" prefer-non-shared="true"> - <language-scope id="org.eclipse.cdt.core.gcc"/> - <language-scope id="org.eclipse.cdt.core.g++"/> - </provider> - </extension> - </configuration> - <configuration id="cdt.managedbuild.config.gnu.cross.exe.release.516195201.976458850.241502451.1275216290" name="DuetEthernet"> - <extension point="org.eclipse.cdt.core.LanguageSettingsProvider"> - <provider copy-of="extension" id="org.eclipse.cdt.ui.UserLanguageSettingsProvider"/> - <provider-reference id="org.eclipse.cdt.core.ReferencedProjectsLanguageSettingsProvider" ref="shared-provider"/> - <provider-reference id="org.eclipse.cdt.managedbuilder.core.MBSLanguageSettingsProvider" ref="shared-provider"/> - <provider class="org.eclipse.cdt.internal.build.crossgcc.CrossGCCBuiltinSpecsDetector" console="false" env-hash="-1419419586637520295" id="org.eclipse.cdt.build.crossgcc.CrossGCCBuiltinSpecsDetector" keep-relative-paths="false" name="CDT Cross GCC Built-in Compiler Settings" parameter="${COMMAND} ${FLAGS} -E -P -v -dD "${INPUTS}"" prefer-non-shared="true"> + <provider class="org.eclipse.cdt.internal.build.crossgcc.CrossGCCBuiltinSpecsDetector" console="false" env-hash="1189573167678144698" id="org.eclipse.cdt.build.crossgcc.CrossGCCBuiltinSpecsDetector" keep-relative-paths="false" name="CDT Cross GCC Built-in Compiler Settings" parameter="${COMMAND} ${FLAGS} -E -P -v -dD "${INPUTS}"" prefer-non-shared="true"> <language-scope id="org.eclipse.cdt.core.gcc"/> <language-scope id="org.eclipse.cdt.core.g++"/> </provider> @@ -49,7 +38,7 @@ <provider copy-of="extension" id="org.eclipse.cdt.ui.UserLanguageSettingsProvider"/> <provider-reference id="org.eclipse.cdt.core.ReferencedProjectsLanguageSettingsProvider" ref="shared-provider"/> <provider-reference id="org.eclipse.cdt.managedbuilder.core.MBSLanguageSettingsProvider" ref="shared-provider"/> - <provider class="org.eclipse.cdt.internal.build.crossgcc.CrossGCCBuiltinSpecsDetector" console="false" env-hash="-1419419586637520295" id="org.eclipse.cdt.build.crossgcc.CrossGCCBuiltinSpecsDetector" keep-relative-paths="false" name="CDT Cross GCC Built-in Compiler Settings" parameter="${COMMAND} ${FLAGS} -E -P -v -dD "${INPUTS}"" prefer-non-shared="true"> + <provider class="org.eclipse.cdt.internal.build.crossgcc.CrossGCCBuiltinSpecsDetector" console="false" env-hash="1189573167678144698" id="org.eclipse.cdt.build.crossgcc.CrossGCCBuiltinSpecsDetector" keep-relative-paths="false" name="CDT Cross GCC Built-in Compiler Settings" parameter="${COMMAND} ${FLAGS} -E -P -v -dD "${INPUTS}"" prefer-non-shared="true"> <language-scope id="org.eclipse.cdt.core.gcc"/> <language-scope id="org.eclipse.cdt.core.g++"/> </provider> @@ -60,7 +49,7 @@ <provider copy-of="extension" id="org.eclipse.cdt.ui.UserLanguageSettingsProvider"/> <provider-reference id="org.eclipse.cdt.core.ReferencedProjectsLanguageSettingsProvider" ref="shared-provider"/> <provider-reference id="org.eclipse.cdt.managedbuilder.core.MBSLanguageSettingsProvider" ref="shared-provider"/> - <provider class="org.eclipse.cdt.internal.build.crossgcc.CrossGCCBuiltinSpecsDetector" console="false" env-hash="-1419419586637520295" id="org.eclipse.cdt.build.crossgcc.CrossGCCBuiltinSpecsDetector" keep-relative-paths="false" name="CDT Cross GCC Built-in Compiler Settings" parameter="${COMMAND} ${FLAGS} -E -P -v -dD "${INPUTS}"" prefer-non-shared="true"> + <provider class="org.eclipse.cdt.internal.build.crossgcc.CrossGCCBuiltinSpecsDetector" console="false" env-hash="1189573167678144698" id="org.eclipse.cdt.build.crossgcc.CrossGCCBuiltinSpecsDetector" keep-relative-paths="false" name="CDT Cross GCC Built-in Compiler Settings" parameter="${COMMAND} ${FLAGS} -E -P -v -dD "${INPUTS}"" prefer-non-shared="true"> <language-scope id="org.eclipse.cdt.core.gcc"/> <language-scope id="org.eclipse.cdt.core.g++"/> </provider> @@ -71,7 +60,7 @@ <provider copy-of="extension" id="org.eclipse.cdt.ui.UserLanguageSettingsProvider"/> <provider-reference id="org.eclipse.cdt.core.ReferencedProjectsLanguageSettingsProvider" ref="shared-provider"/> <provider-reference id="org.eclipse.cdt.managedbuilder.core.MBSLanguageSettingsProvider" ref="shared-provider"/> - <provider class="org.eclipse.cdt.internal.build.crossgcc.CrossGCCBuiltinSpecsDetector" console="false" env-hash="-1419419586637520295" id="org.eclipse.cdt.build.crossgcc.CrossGCCBuiltinSpecsDetector" keep-relative-paths="false" name="CDT Cross GCC Built-in Compiler Settings" parameter="${COMMAND} ${FLAGS} -E -P -v -dD "${INPUTS}"" prefer-non-shared="true"> + <provider class="org.eclipse.cdt.internal.build.crossgcc.CrossGCCBuiltinSpecsDetector" console="false" env-hash="1189573167678144698" id="org.eclipse.cdt.build.crossgcc.CrossGCCBuiltinSpecsDetector" keep-relative-paths="false" name="CDT Cross GCC Built-in Compiler Settings" parameter="${COMMAND} ${FLAGS} -E -P -v -dD "${INPUTS}"" prefer-non-shared="true"> <language-scope id="org.eclipse.cdt.core.gcc"/> <language-scope id="org.eclipse.cdt.core.g++"/> </provider> diff --git a/EdgeRelease/1.21RC3/Duet2CombinedFirmware.bin b/EdgeRelease/1.21RC3/Duet2CombinedFirmware.bin Binary files differnew file mode 100644 index 00000000..17187665 --- /dev/null +++ b/EdgeRelease/1.21RC3/Duet2CombinedFirmware.bin diff --git a/EdgeRelease/1.21RC3/DuetMaestroFirmware.bin b/EdgeRelease/1.21RC3/DuetMaestroFirmware.bin Binary files differnew file mode 100644 index 00000000..b4cf1a8d --- /dev/null +++ b/EdgeRelease/1.21RC3/DuetMaestroFirmware.bin diff --git a/EdgeRelease/1.21RC3/DuetWebControl-1.21-RC4.zip b/EdgeRelease/1.21RC3/DuetWebControl-1.21-RC4.zip Binary files differnew file mode 100644 index 00000000..076a95b0 --- /dev/null +++ b/EdgeRelease/1.21RC3/DuetWebControl-1.21-RC4.zip diff --git a/EdgeRelease/1.21RC3/DuetWiFiServer.bin b/EdgeRelease/1.21RC3/DuetWiFiServer.bin Binary files differnew file mode 100644 index 00000000..ebe60d3a --- /dev/null +++ b/EdgeRelease/1.21RC3/DuetWiFiServer.bin diff --git a/EdgeRelease/1.21RC3/RepRapFirmware-Alligator.bin b/EdgeRelease/1.21RC3/RepRapFirmware-Alligator.bin Binary files differnew file mode 100644 index 00000000..7b305013 --- /dev/null +++ b/EdgeRelease/1.21RC3/RepRapFirmware-Alligator.bin diff --git a/EdgeRelease/1.21RC3/RepRapFirmware-RADDS.bin b/EdgeRelease/1.21RC3/RepRapFirmware-RADDS.bin Binary files differnew file mode 100644 index 00000000..8db5a611 --- /dev/null +++ b/EdgeRelease/1.21RC3/RepRapFirmware-RADDS.bin diff --git a/EdgeRelease/1.21RC3/RepRapFirmware.bin b/EdgeRelease/1.21RC3/RepRapFirmware.bin Binary files differnew file mode 100644 index 00000000..2876c7fe --- /dev/null +++ b/EdgeRelease/1.21RC3/RepRapFirmware.bin diff --git a/src/Configuration.h b/src/Configuration.h index 0391aa2d..dd62b566 100644 --- a/src/Configuration.h +++ b/src/Configuration.h @@ -25,18 +25,6 @@ Licence: GPL #include <cstddef> // for size_t -// Other firmware that we might switch to be compatible with. - -enum Compatibility -{ - me = 0, - reprapFirmware = 1, - marlin = 2, - teacup = 3, - sprinter = 4, - repetier = 5 -}; - // Generic constants constexpr float ABS_ZERO = -273.15; // Celsius constexpr float NEARLY_ABS_ZERO = -273.0; // Celsius @@ -220,6 +208,7 @@ constexpr size_t RESERVED_OUTPUT_BUFFERS = 2; // Number of reserved output buf constexpr float DefaultFeedrate = 3000.0; // The initial requested feed rate after resetting the printer, in mm/min constexpr float DefaultRetractSpeed = 1000.0; // The default firmware retraction and un-retraction speed, in mm constexpr float DefaultRetractLength = 2.0; +constexpr float MinimumMovementSpeed = 0.5; // The minimum movement speed (extruding moves will go slower than this if the extrusion rate demands it) constexpr float DefaultArcSegmentLength = 0.2; // G2 and G3 arc movement commands get split into segments this long @@ -227,6 +216,7 @@ constexpr uint32_t DefaultIdleTimeout = 30000; // Milliseconds constexpr float DefaultIdleCurrentFactor = 0.3; // Proportion of normal motor current that we use for idle hold constexpr float DefaultNonlinearExtrusionLimit = 0.2; // Maximum additional commanded extrusion to compensate for nonlinearity +constexpr size_t NumRestorePoints = 3; // Number of restore points, must be at least 3 // Triggers constexpr unsigned int MaxTriggers = 10; // Must be <= 32 because we store a bitmap of pending triggers in a uint32_t diff --git a/src/DuetM/TMC22xx.cpp b/src/DuetM/TMC22xx.cpp index aa6df647..b9ab6f4f 100644 --- a/src/DuetM/TMC22xx.cpp +++ b/src/DuetM/TMC22xx.cpp @@ -22,7 +22,7 @@ const bool DefaultInterpolation = true; // interpolation enabled // So at 500kbaud it takes about 128us to write a register, and 192us+ to read a register. // In testing I found that 500kbaud was not reliable, so now using 200kbaud. const uint32_t DriversBaudRate = 200000; -const uint32_t TransferTimeout = 10; // any transfer should complete within 10 ticks +const uint32_t TransferTimeout = 10; // any transfer should complete within 10 ticks @ 1ms/tick static size_t numTmc22xxDrivers; @@ -225,20 +225,6 @@ static inline constexpr uint8_t CRCAddByte(uint8_t crc, uint8_t currentByte) return crc; } -#if 0 // unused -// Calculate the CRC of a message -static uint8_t CalcCRC(const uint8_t *datagram, uint8_t length) -{ - uint8_t crc = 0; - do - { - crc = CRCAddByte(crc, *datagram++); - } - while (--length != 0); - return crc; -} -#endif - // CRC of the first 2 bytes we send in any request static constexpr uint8_t InitialSendCRC = CRCAddByte(CRCAddByte(0, 0x05), 0x00); @@ -278,6 +264,9 @@ public: uint8_t GetDriverNumber() const { return driverNumber; } bool UpdatePending() const { return registersToUpdate != 0; } + float GetStandstillCurrentPercent() const; + void SetStandstillCurrentPercent(float percent); + void TransferDone() __attribute__ ((hot)); // called by the ISR when the SPI transfer has completed void StartTransfer() __attribute__ ((hot)); // called to start a transfer void TransferTimedOut() { ++numTimeouts; } @@ -289,7 +278,8 @@ public: private: void UpdateRegister(size_t regIndex, uint32_t regVal); - void UpdateChopConfRegister(); // calculate the copper control register and flag it for sending + void UpdateChopConfRegister(); // calculate the chopper control register and flag it for sending + void UpdateCurrent(); void SetUartMux(); static constexpr unsigned int NumWriteRegisters = 5; // the number of registers that we write to @@ -312,16 +302,17 @@ private: static void SetupDMASend(uint8_t regnum, uint32_t outVal, uint8_t crc) __attribute__ ((hot)); // set up the PDC to send a register static void SetupDMAReceive(uint8_t regnum, uint8_t crc) __attribute__ ((hot)); // set up the PDC to receive a register - uint32_t writeRegisters[NumWriteRegisters]; // the values we want the TMC22xx writable registers to have + volatile uint32_t writeRegisters[NumWriteRegisters]; // the values we want the TMC22xx writable registers to have volatile uint32_t readRegisters[NumReadRegisters]; // the last values read from the TMC22xx readable registers volatile uint32_t accumulatedReadRegisters[NumReadRegisters]; uint32_t configuredChopConfReg; // the configured chopper control register, in the Enabled state, without the microstepping bits - uint32_t registersToUpdate; // bitmap of register indices whose values need to be sent to the driver chip - uint32_t registerBeingUpdated; // which register we are sending + volatile uint32_t registersToUpdate; // bitmap of register indices whose values need to be sent to the driver chip + volatile uint32_t registerBeingUpdated; // which register we are sending uint32_t axisNumber; // the axis number of this driver as used to index the DriveMovements in the DDA uint32_t microstepShiftFactor; // how much we need to shift 1 left by to get the current microstepping + uint32_t motorCurrent; // the configured motor current uint16_t readErrors; // how many read errors we had uint16_t writeErrors; // how many write errors we had @@ -330,9 +321,10 @@ private: Pin enablePin; // the enable pin of this driver, if it has its own uint8_t driverNumber; // the number of this driver as addressed by the UART multiplexer - uint8_t writeRegCRCs[NumWriteRegisters]; // CRCs of the messages needed to update the registers + uint8_t standstillCurrentFraction; // divide this by 256 to get the motor current standstill fraction uint8_t registerToRead; // the next register we need to read uint8_t lastIfCount; // the value of the IFCNT register last time we read it + volatile uint8_t writeRegCRCs[NumWriteRegisters]; // CRCs of the messages needed to update the registers static const uint8_t ReadRegCRCs[NumReadRegisters]; // CRCs of the messages needed to read the registers bool enabled; // true if driver is enabled }; @@ -436,18 +428,20 @@ void TmcDriverState::Init(uint32_t p_driverNumber, Pin p_pin) pre(!driversPowered) { driverNumber = p_driverNumber; - axisNumber = p_driverNumber; // assume straight-through axis mapping initially - enablePin = p_pin; // this is NoPin for the built-in drivers + axisNumber = p_driverNumber; // assume straight-through axis mapping initially + enablePin = p_pin; // this is NoPin for the built-in drivers if (p_pin != NoPin) { pinMode(p_pin, OUTPUT_HIGH); } enabled = false; registersToUpdate = 0; + motorCurrent = 0; + standstillCurrentFraction = (256 * 3)/4; // default to 75% UpdateRegister(WriteGConf, DefaultGConfReg); UpdateRegister(WriteSlaveConf, DefaultSlaveConfReg); configuredChopConfReg = DefaultChopConfReg; - SetMicrostepping(DefaultMicrosteppingShift, DefaultInterpolation); // this also updates the chopper control register + SetMicrostepping(DefaultMicrosteppingShift, DefaultInterpolation); // this also updates the chopper control register UpdateRegister(WriteIholdIrun, DefaultIholdIrunReg); UpdateRegister(WritePwmConf, DefaultPwmConfReg); for (size_t i = 0; i < NumReadRegisters; ++i) @@ -471,6 +465,17 @@ inline void TmcDriverState::WriteAll() registersToUpdate = (1u << NumWriteRegisters) - 1; } +float TmcDriverState::GetStandstillCurrentPercent() const +{ + return (float)(standstillCurrentFraction * 100)/256; +} + +void TmcDriverState::SetStandstillCurrentPercent(float percent) +{ + standstillCurrentFraction = (uint8_t)constrain<long>(lrintf((percent * 256)/100), 0, 255); + UpdateCurrent(); +} + // Set the chopper control register to the settings provided by the user void TmcDriverState::SetChopConf(uint32_t newVal) { @@ -493,12 +498,17 @@ void TmcDriverState::SetMicrostepping(uint32_t shift, bool interpolate) // Set the motor current void TmcDriverState::SetCurrent(float current) { - // The current sense resistor on the Duet M is 0.091 ohms, to which we must add 0.02 ohms internal resistance. - // Full scale peak motor current in the high sensitivity range is give by I = 0.18/(R+0.02) = 0.18/0.111 ~= 1.6A + motorCurrent = static_cast<uint32_t>(constrain<float>(current, 50.0, MaximumMotorCurrent)); + UpdateCurrent(); +} + +void TmcDriverState::UpdateCurrent() +{ + // The current sense resistor on the Duet M is 0.075 ohms, to which we must add 0.03 ohms internal resistance. + // Full scale peak motor current in the high sensitivity range is give by I = 0.18/(R+0.03) = 0.18/0.105 ~= 1.6A // This gives us a range of 50mA to 1.6A in 50mA steps in the high sensitivity range (VSENSE = 1) - const uint32_t iRunCurrent = static_cast<uint32_t>(constrain<float>(current, 50.0, MaximumMotorCurrent)); - const uint32_t iRunCsBits = (32 * iRunCurrent - 800)/1615; // formula checked by simulation on a spreadsheet - const uint32_t iHoldCurrent = (iRunCurrent * 3)/4; // set standstill current to 3/4 of run current + const uint32_t iRunCsBits = (32 * motorCurrent - 800)/1615; // formula checked by simulation on a spreadsheet + const uint32_t iHoldCurrent = (motorCurrent * standstillCurrentFraction)/256; // set standstill current const uint32_t iHoldCsBits = (32 * iHoldCurrent - 800)/1615; // formula checked by simulation on a spreadsheet UpdateRegister(WriteIholdIrun, (writeRegisters[WriteIholdIrun] & ~(IHOLDIRUN_IRUN_MASK | IHOLDIRUN_IHOLD_MASK)) | (iRunCsBits << IHOLDIRUN_IRUN_SHIFT) | (iHoldCsBits << IHOLDIRUN_IHOLD_SHIFT)); @@ -931,6 +941,20 @@ namespace SmartDrivers } } + float GetStandstillCurrentPercent(size_t drive) + { + return (drive < numTmc22xxDrivers) ? driverStates[drive].GetStandstillCurrentPercent() : 0.0; + } + + void SetStandstillCurrentPercent(size_t drive, float percent) + { + if (drive < numTmc22xxDrivers) + { + driverStates[drive].SetStandstillCurrentPercent(percent); + } + + } + }; // end namespace // End diff --git a/src/DuetM/TMC22xx.h b/src/DuetM/TMC22xx.h index 2894e7fd..69a8f976 100644 --- a/src/DuetM/TMC22xx.h +++ b/src/DuetM/TMC22xx.h @@ -47,6 +47,8 @@ namespace SmartDrivers void TurnDriversOff(); void SetCoolStep(size_t drive, uint16_t coolStepConfig); void AppendDriverStatus(size_t drive, const StringRef& reply); + float GetStandstillCurrentPercent(size_t drive); + void SetStandstillCurrentPercent(size_t drive, float percent); }; #endif /* TMC2660_H_ */ diff --git a/src/DuetNG/DueXn.cpp b/src/DuetNG/DueXn.cpp index ac41382b..25e8969b 100644 --- a/src/DuetNG/DueXn.cpp +++ b/src/DuetNG/DueXn.cpp @@ -88,7 +88,7 @@ namespace DuetExpansion // Set up the interrupt on any input change dueXnInputMask = stopBits | AllGpioBits; - dueXnExpander.enableInterruptMultiple(dueXnInputMask, CHANGE); + dueXnExpander.enableInterruptMultiple(dueXnInputMask, INTERRUPT_MODE_CHANGE); // Clear any initial interrupts (void)dueXnExpander.interruptSource(true); diff --git a/src/DuetNG/Pins_DuetNG.h b/src/DuetNG/Pins_DuetNG.h index 62fbcdec..249a3c1e 100644 --- a/src/DuetNG/Pins_DuetNG.h +++ b/src/DuetNG/Pins_DuetNG.h @@ -1,10 +1,10 @@ #ifndef PINS_DUETNG_H__ #define PINS_DUETNG_H__ -# define FIRMWARE_NAME "RepRapFirmware for Duet WiFi and Duet Ethernet" +# define FIRMWARE_NAME "RepRapFirmware for Duet 2 WiFi/Ethernet" # define DEFAULT_BOARD_TYPE BoardType::DuetWiFi_10 constexpr size_t NumFirmwareUpdateModules = 4; // 3 modules, plus one for manual upload to WiFi module (module 2 is now unused) -# define IAP_FIRMWARE_FILE "DuetWiFiFirmware.bin" +# define IAP_FIRMWARE_FILE "Duet2CombinedFirmware.bin" # define WIFI_FIRMWARE_FILE "DuetWiFiServer.bin" // Features definition diff --git a/src/DuetNG/SX1509.cpp b/src/DuetNG/SX1509.cpp index 1f8ea75d..9b7a54d7 100644 --- a/src/DuetNG/SX1509.cpp +++ b/src/DuetNG/SX1509.cpp @@ -531,13 +531,13 @@ void SX1509::enableInterruptMultiple(uint16_t pins, uint8_t riseFall) uint8_t sensitivity; switch (riseFall) { - case CHANGE: + case INTERRUPT_MODE_CHANGE: sensitivity = 0b11; break; - case FALLING: + case INTERRUPT_MODE_FALLING: sensitivity = 0b10; break; - case RISING: + case INTERRUPT_MODE_RISING: sensitivity = 0b01; break; default: diff --git a/src/DuetNG/TMC2660.cpp b/src/DuetNG/TMC2660.cpp index c077954d..c5b0414a 100644 --- a/src/DuetNG/TMC2660.cpp +++ b/src/DuetNG/TMC2660.cpp @@ -731,6 +731,16 @@ namespace SmartDrivers } } + float GetStandstillCurrentPercent(size_t drive) + { + return 100.0; // not supported + } + + void SetStandstillCurrentPercent(size_t drive, float percent) + { + // not supported so nothing to see here + } + }; // end namespace // End diff --git a/src/DuetNG/TMC2660.h b/src/DuetNG/TMC2660.h index 6734d84a..8e07f75a 100644 --- a/src/DuetNG/TMC2660.h +++ b/src/DuetNG/TMC2660.h @@ -48,6 +48,8 @@ namespace SmartDrivers void SetCoolStep(size_t drive, uint16_t coolStepConfig); void AppendStallConfig(size_t drive, const StringRef& reply); void AppendDriverStatus(size_t drive, const StringRef& reply); + float GetStandstillCurrentPercent(size_t drive); + void SetStandstillCurrentPercent(size_t drive, float percent); }; #endif /* TMC2660_H_ */ diff --git a/src/FilamentMonitors/FilamentMonitor.cpp b/src/FilamentMonitors/FilamentMonitor.cpp index a3b3d44a..64458396 100644 --- a/src/FilamentMonitors/FilamentMonitor.cpp +++ b/src/FilamentMonitors/FilamentMonitor.cpp @@ -30,7 +30,7 @@ FilamentMonitor::~FilamentMonitor() // Try to get the pin number from the GCode command in the buffer, setting Seen if a pin number was provided and returning true if error. // Also attaches the ISR. -bool FilamentMonitor::ConfigurePin(GCodeBuffer& gb, const StringRef& reply, uint32_t interruptMode, bool& seen) +bool FilamentMonitor::ConfigurePin(GCodeBuffer& gb, const StringRef& reply, InterruptMode interruptMode, bool& seen) { if (gb.Seen('C')) { @@ -46,7 +46,7 @@ bool FilamentMonitor::ConfigurePin(GCodeBuffer& gb, const StringRef& reply, uint endstopNumber = endstop; pin = p; haveIsrStepsCommanded = false; - if (!attachInterrupt(pin, InterruptEntry, interruptMode, this)) + if (interruptMode != INTERRUPT_MODE_NONE && !attachInterrupt(pin, InterruptEntry, interruptMode, this)) { reply.copy("unsuitable endstop number"); return true; diff --git a/src/FilamentMonitors/FilamentMonitor.h b/src/FilamentMonitors/FilamentMonitor.h index 9429910a..1fa4416f 100644 --- a/src/FilamentMonitors/FilamentMonitor.h +++ b/src/FilamentMonitors/FilamentMonitor.h @@ -63,7 +63,7 @@ public: protected: FilamentMonitor(unsigned int extruder, int t) : extruderNumber(extruder), type(t), pin(NoPin) { } - bool ConfigurePin(GCodeBuffer& gb, const StringRef& reply, uint32_t interruptMode, bool& seen); + bool ConfigurePin(GCodeBuffer& gb, const StringRef& reply, InterruptMode interruptMode, bool& seen); int GetEndstopNumber() const { return endstopNumber; } diff --git a/src/FilamentMonitors/LaserFilamentMonitor.cpp b/src/FilamentMonitors/LaserFilamentMonitor.cpp index ac5c2552..cdf544f2 100644 --- a/src/FilamentMonitors/LaserFilamentMonitor.cpp +++ b/src/FilamentMonitors/LaserFilamentMonitor.cpp @@ -40,7 +40,7 @@ void LaserFilamentMonitor::Reset() // Configure this sensor, returning true if error and setting 'seen' if we processed any configuration parameters bool LaserFilamentMonitor::Configure(GCodeBuffer& gb, const StringRef& reply, bool& seen) { - if (ConfigurePin(gb, reply, CHANGE, seen)) + if (ConfigurePin(gb, reply, INTERRUPT_MODE_CHANGE, seen)) { return true; } diff --git a/src/FilamentMonitors/PulsedFilamentMonitor.cpp b/src/FilamentMonitors/PulsedFilamentMonitor.cpp index 9bb049a4..fb9f440e 100644 --- a/src/FilamentMonitors/PulsedFilamentMonitor.cpp +++ b/src/FilamentMonitors/PulsedFilamentMonitor.cpp @@ -34,7 +34,7 @@ void PulsedFilamentMonitor::Reset() // Configure this sensor, returning true if error and setting 'seen' if we processed any configuration parameters bool PulsedFilamentMonitor::Configure(GCodeBuffer& gb, const StringRef& reply, bool& seen) { - if (ConfigurePin(gb, reply, RISING, seen)) + if (ConfigurePin(gb, reply, INTERRUPT_MODE_RISING, seen)) { return true; } diff --git a/src/FilamentMonitors/RotatingMagnetFilamentMonitor.cpp b/src/FilamentMonitors/RotatingMagnetFilamentMonitor.cpp index 58d6466d..bed228e6 100644 --- a/src/FilamentMonitors/RotatingMagnetFilamentMonitor.cpp +++ b/src/FilamentMonitors/RotatingMagnetFilamentMonitor.cpp @@ -39,7 +39,7 @@ void RotatingMagnetFilamentMonitor::Reset() // Configure this sensor, returning true if error and setting 'seen' if we processed any configuration parameters bool RotatingMagnetFilamentMonitor::Configure(GCodeBuffer& gb, const StringRef& reply, bool& seen) { - if (ConfigurePin(gb, reply, CHANGE, seen)) + if (ConfigurePin(gb, reply, INTERRUPT_MODE_CHANGE, seen)) { return true; } @@ -165,7 +165,7 @@ float RotatingMagnetFilamentMonitor::GetCurrentPosition() const } // Call the following at intervals to check the status. This is only called when extrusion is in progress or imminent. -// 'filamentConsumed' is the net amount of extrusion since the last call to this function. +// 'filamentConsumed' is the net amount of extrusion commanded since the last call to this function. // 'hadNonPrintingMove' is called if filamentConsumed includes extruder movement form non-printing moves. FilamentSensorStatus RotatingMagnetFilamentMonitor::Check(bool full, bool hadNonPrintingMove, bool fromIsr, float filamentConsumed) { @@ -230,6 +230,8 @@ FilamentSensorStatus RotatingMagnetFilamentMonitor::CheckFilament(float amountCo } FilamentSensorStatus ret = FilamentSensorStatus::ok; + const float extrusionMeasured = amountMeasured * mmPerRev; + if (!comparisonStarted) { // The first measurement after we start extruding is often a long way out, so discard it @@ -241,7 +243,6 @@ FilamentSensorStatus RotatingMagnetFilamentMonitor::CheckFilament(float amountCo const float minExtrusionExpected = (amountCommanded >= 0.0) ? amountCommanded * minMovementAllowed : amountCommanded * maxMovementAllowed; - const float extrusionMeasured = amountMeasured * mmPerRev; if (extrusionMeasured < minExtrusionExpected) { ret = FilamentSensorStatus::tooLittleMovement; @@ -259,7 +260,7 @@ FilamentSensorStatus RotatingMagnetFilamentMonitor::CheckFilament(float amountCo } // Update the calibration accumulators, even if the user hasn't asked to do calibration - const float ratio = amountMeasured/amountCommanded; + const float ratio = extrusionMeasured/amountCommanded; if (calibrationStarted) { if (ratio < minMovementRatio) diff --git a/src/FilamentMonitors/RotatingMagnetFilamentMonitor.h b/src/FilamentMonitors/RotatingMagnetFilamentMonitor.h index fd660b2a..88e0cbe1 100644 --- a/src/FilamentMonitors/RotatingMagnetFilamentMonitor.h +++ b/src/FilamentMonitors/RotatingMagnetFilamentMonitor.h @@ -49,15 +49,15 @@ private: uint16_t switchOpenMask; // mask to isolate the switch open bit(s) from the sensor value uint32_t framingErrorCount; // the number of framing errors we received - float extrusionCommandedAtStartBit; // the amount of extrusion commanded since the previous comparison when we received the start bit - float extrusionCommandedSinceLastSync; - float movementMeasuredSinceLastSync; + float extrusionCommandedAtStartBit; // the amount of extrusion commanded (mm) when we received the start bit since the last sync + float extrusionCommandedSinceLastSync; // the amount of extrusion commanded (mm) since the last sync + float movementMeasuredSinceLastSync; // the amount of movement in complete rotations of the wheel since the last sync bool hadNonPrintingMoveAtStartBit; bool hadNonPrintingMoveSinceLastSync; bool haveStartBitData; - float extrusionCommandedThisSegment; // the amount of extrusion commanded since we last did a comparison - float movementMeasuredThisSegment; // the accumulated movement since the previous comparison + float extrusionCommandedThisSegment; // the amount of extrusion commanded (mm) since we last did a comparison + float movementMeasuredThisSegment; // the accumulated movement in complete rotations since the previous comparison // Values measured for calibration float minMovementRatio, maxMovementRatio; diff --git a/src/FilamentMonitors/SimpleFilamentMonitor.cpp b/src/FilamentMonitors/SimpleFilamentMonitor.cpp index 6a623e8e..5956fa71 100644 --- a/src/FilamentMonitors/SimpleFilamentMonitor.cpp +++ b/src/FilamentMonitors/SimpleFilamentMonitor.cpp @@ -17,7 +17,7 @@ SimpleFilamentMonitor::SimpleFilamentMonitor(unsigned int extruder, int type) // Configure this sensor, returning true if error and setting 'seen' if we processed any configuration parameters bool SimpleFilamentMonitor::Configure(GCodeBuffer& gb, const StringRef& reply, bool& seen) { - if (ConfigurePin(gb, reply, CHANGE, seen)) + if (ConfigurePin(gb, reply, INTERRUPT_MODE_NONE, seen)) { return true; } diff --git a/src/GCodes/GCodeBuffer.cpp b/src/GCodes/GCodeBuffer.cpp index d65512a2..36fe9e95 100644 --- a/src/GCodes/GCodeBuffer.cpp +++ b/src/GCodes/GCodeBuffer.cpp @@ -950,6 +950,13 @@ bool GCodeBuffer::PopState() return true; } +// Abort execution of any files or macros being executed +void GCodeBuffer::AbortFile() +{ + while (PopState()) { } // abandon any macros + machineState->fileState.Close(); // if we are executing a file, abandon it +} + // Return true if this source is executing a file macro bool GCodeBuffer::IsDoingFileMacro() const { diff --git a/src/GCodes/GCodeBuffer.h b/src/GCodes/GCodeBuffer.h index 8620632f..fb64ff6f 100644 --- a/src/GCodes/GCodeBuffer.h +++ b/src/GCodes/GCodeBuffer.h @@ -67,9 +67,12 @@ public: GCodeMachineState& OriginalMachineState() const; bool PushState(); // Push state returning true if successful (i.e. stack not overflowed) bool PopState(); // Pop state returning true if successful (i.e. no stack underrun) + void AbortFile(); // Abort execution of any files or macros being executed + bool IsDoingFileMacro() const; // Return true if this source is executing a file macro GCodeState GetState() const; void SetState(GCodeState newState); + void SetState(GCodeState newState, const char *err); void AdvanceState(); const char *GetIdentity() const { return identity; } bool CanQueueCodes() const; @@ -204,6 +207,12 @@ inline void GCodeBuffer::SetState(GCodeState newState) machineState->state = newState; } +inline void GCodeBuffer::SetState(GCodeState newState, const char *err) +{ + machineState->state = newState; + machineState->err = err; +} + inline void GCodeBuffer::AdvanceState() { machineState->state = static_cast<GCodeState>(static_cast<uint8_t>(machineState->state) + 1); diff --git a/src/GCodes/GCodeMachineState.cpp b/src/GCodes/GCodeMachineState.cpp index d4a600eb..a0f49eaf 100644 --- a/src/GCodes/GCodeMachineState.cpp +++ b/src/GCodes/GCodeMachineState.cpp @@ -12,7 +12,7 @@ unsigned int GCodeMachineState::numAllocated = 0; // Create a default initialised GCodeMachineState GCodeMachineState::GCodeMachineState() - : previous(nullptr), feedrate(DefaultFeedrate * SecondsToMinutes), fileState(), lockedResources(0), state(GCodeState::normal), + : previous(nullptr), feedrate(DefaultFeedrate * SecondsToMinutes), fileState(), lockedResources(0), err(nullptr), state(GCodeState::normal), drivesRelative(false), axesRelative(false), doingFileMacro(false), runningM501(false), runningM502(false), volumetricExtrusion(false), waitingForAcknowledgement(false), messageAcknowledged(false) { } @@ -25,6 +25,7 @@ GCodeMachineState::GCodeMachineState() { freeList = ms->previous; ms->lockedResources = 0; + ms->err = nullptr; ms->state = GCodeState::normal; } else diff --git a/src/GCodes/GCodeMachineState.h b/src/GCodes/GCodeMachineState.h index 6736415c..bacd9aac 100644 --- a/src/GCodes/GCodeMachineState.h +++ b/src/GCodes/GCodeMachineState.h @@ -17,6 +17,7 @@ enum class GCodeState : uint8_t normal, // not doing anything and ready to process a new GCode waitingForSpecialMoveToComplete, // doing a special move, so we must wait for it to finish before processing another GCode + waitingForArcMoveToComplete, // doing an arc move, so we must check whether it completes normally probingToolOffset, @@ -91,6 +92,7 @@ public: float feedrate; FileData fileState; ResourceBitmap lockedResources; + const char *err; GCodeState state; uint8_t toolChangeParam; int16_t newToolNumber; diff --git a/src/GCodes/GCodes.cpp b/src/GCodes/GCodes.cpp index a3783016..cb1e5a29 100644 --- a/src/GCodes/GCodes.cpp +++ b/src/GCodes/GCodes.cpp @@ -191,12 +191,14 @@ void GCodes::Reset() reprap.GetMove().GetKinematics().GetAssumedInitialPosition(numVisibleAxes, moveBuffer.coords); ToolOffsetInverseTransform(moveBuffer.coords, currentUserPosition); - pauseRestorePoint.Init(); - toolChangeRestorePoint.Init(); + for (RestorePoint& rp : numberedRestorePoints) + { + rp.Init(); + } - for (size_t i = 0; i < MaxTriggers; ++i) + for (Trigger& tr : triggers) { - triggers[i].Init(); + tr.Init(); } triggersPending = 0; @@ -217,7 +219,7 @@ void GCodes::Reset() lastFilamentError = FilamentSensorStatus::ok; codeQueue->Clear(); - cancelWait = isWaiting = displayNoToolWarning = displayDeltaNotHomedWarning = false; + cancelWait = isWaiting = displayNoToolWarning = false; for (size_t i = 0; i < NumResources; ++i) { @@ -344,12 +346,6 @@ void GCodes::Spin() displayNoToolWarning = false; lastWarningMillis = now; } - if (displayDeltaNotHomedWarning) - { - platform.Message(ErrorMessage, "Attempt to move the head of a Delta or SCARA printer before homing it\n"); - displayDeltaNotHomedWarning = false; - lastWarningMillis = now; - } } platform.ClassReport(longWait); } @@ -387,6 +383,27 @@ void GCodes::RunStateMachine(GCodeBuffer& gb, const StringRef& reply) } break; + case GCodeState::waitingForArcMoveToComplete: + // Wait for all segments of the arc move to go and check whether an error occurred + if (!doingArcMove || segmentsLeft == 0) + { + if (abortedArcMove) + { + if (!LockMovementAndWaitForStandstill(gb)) // update the the user position from the machine position at which we stop + { + break; + } + reply.copy("G2/G3: outside machine limits"); + error = true; + if (machineType != MachineType::fff) + { + AbortPrint(gb); + } + } + gb.SetState(GCodeState::normal); + } + break; + case GCodeState::probingToolOffset: if (LockMovementAndWaitForStandstill(gb)) { @@ -716,6 +733,11 @@ void GCodes::RunStateMachine(GCodeBuffer& gb, const StringRef& reply) moveBuffer.yAxes = DefaultYAxisMapping; totalSegments = 1; segmentsLeft = 1; + + tapsDone = 0; + g30zHeightErrorSum = 0.0; + g30zHeightErrorLowestDiff = 1000.0; + gb.AdvanceState(); } else @@ -731,7 +753,7 @@ void GCodes::RunStateMachine(GCodeBuffer& gb, const StringRef& reply) } break; - case GCodeState::gridProbing2a: // ready to probe the current grid probe point + case GCodeState::gridProbing2a: // ready to probe the current grid probe point (we return to this state when doing the second and subsequent taps) if (LockMovementAndWaitForStandstill(gb)) { gb.AdvanceState(); @@ -746,9 +768,6 @@ void GCodes::RunStateMachine(GCodeBuffer& gb, const StringRef& reply) if (LockMovementAndWaitForStandstill(gb)) { lastProbedTime = millis(); - tapsDone = 0; - g30zHeightErrorSum = 0.0; - g30zHeightErrorLowestDiff = 1000.0; if (platform.GetZProbeType() != ZProbeType::none && platform.GetCurrentZProbeParameters().turnHeatersOff) { reprap.GetHeat().SuspendHeaters(true); @@ -871,7 +890,7 @@ void GCodes::RunStateMachine(GCodeBuffer& gb, const StringRef& reply) // Tap again lastProbedTime = millis(); g30PrevHeightError = g30zHeightError; - gb.SetState(GCodeState::gridProbing3); + gb.SetState(GCodeState::gridProbing2a); } else { @@ -985,11 +1004,15 @@ void GCodes::RunStateMachine(GCodeBuffer& gb, const StringRef& reply) totalSegments = 1; segmentsLeft = 1; + tapsDone = 0; + g30zHeightErrorSum = 0.0; + g30zHeightErrorLowestDiff = 1000.0; + gb.AdvanceState(); } break; - case GCodeState::probingAtPoint2a: + case GCodeState::probingAtPoint2a: // note we return to this state when doing the second and subsequent taps if (LockMovementAndWaitForStandstill(gb)) { gb.AdvanceState(); @@ -1007,9 +1030,6 @@ void GCodes::RunStateMachine(GCodeBuffer& gb, const StringRef& reply) { // Head has finished moving to the correct XY position lastProbedTime = millis(); // start the probe recovery timer - tapsDone = 0; - g30zHeightErrorSum = 0.0; - g30zHeightErrorLowestDiff = 1000.0; if (platform.GetZProbeType() != ZProbeType::none && platform.GetCurrentZProbeParameters().turnHeatersOff) { reprap.GetHeat().SuspendHeaters(true); @@ -1172,7 +1192,7 @@ void GCodes::RunStateMachine(GCodeBuffer& gb, const StringRef& reply) // Tap again g30PrevHeightError = g30zHeightError; lastProbedTime = millis(); - gb.SetState(GCodeState::probingAtPoint3); + gb.SetState(GCodeState::probingAtPoint2a); } else { @@ -1360,6 +1380,16 @@ void GCodes::RunStateMachine(GCodeBuffer& gb, const StringRef& reply) // We completed a command, so unlock resources and tell the host about it gb.timerRunning = false; UnlockAll(gb); + if (error) + { + gb.MachineState().err = nullptr; // we can't report more than one error here, so clear the original one + } + else if (gb.MachineState().err != nullptr) + { + reply.copy(gb.MachineState().err); + gb.MachineState().err = nullptr; + error = true; + } HandleReply(gb, error, reply.Pointer()); } } @@ -1638,6 +1668,8 @@ void GCodes::DoPause(GCodeBuffer& gb, PauseReason reason, const char *msg) { fdata.Seek(pauseRestorePoint.filePos); // replay the abandoned instructions when we resume fileInput->Reset(); // clear the buffered data + fileGCode->Init(); // clear the next move + UnlockAll(*fileGCode); // release any locks it had } codeQueue->PurgeEntries(); @@ -2191,9 +2223,65 @@ bool GCodes::LoadExtrusionAndFeedrateFromGCode(GCodeBuffer& gb, int moveType) return true; } +// Check that enough axes have been homed +bool GCodes::CheckEnoughAxesHomed(AxesBitmap axesMoved) +{ + // Regular move. If it's a delta or SCARA printer, the XYZ axes must be homed first. + constexpr AxesBitmap xyAxes = MakeBitmap<AxesBitmap>(X_AXIS) | MakeBitmap<AxesBitmap>(Y_AXIS); + constexpr AxesBitmap xyzAxes = xyAxes | MakeBitmap<AxesBitmap>(Z_AXIS); + constexpr AxesBitmap xzAxes = MakeBitmap<AxesBitmap>(X_AXIS) | MakeBitmap<AxesBitmap>(Z_AXIS); + constexpr AxesBitmap uvAxes = MakeBitmap<AxesBitmap>(U_AXIS) | MakeBitmap<AxesBitmap>(V_AXIS); + + switch (reprap.GetMove().GetKinematics().GetKinematicsType()) + { + case KinematicsType::cartesian: + break; + + case KinematicsType::coreXY: + case KinematicsType::coreXYU: + if ((axesMoved & xyAxes) != 0) + { + axesMoved |= xyAxes; + } + break; + + case KinematicsType::coreXZ: + if ((axesMoved & xzAxes) != 0) + { + axesMoved |= xzAxes; + } + break; + + case KinematicsType::coreXYUV: + if ((axesMoved & xyAxes) != 0) + { + axesMoved |= xyAxes; + } + if ((axesMoved & uvAxes) != 0) + { + axesMoved |= uvAxes; + } + break; + + case KinematicsType::linearDelta: + case KinematicsType::polar: + case KinematicsType::scara: + case KinematicsType::hangprinter: + default: + // For these printers we require all of XYZ to be homed before any normal movements are made + if ((axesMoved & xyzAxes) != 0) + { + axesMoved |= xyzAxes; + } + break; + } + + return (axesMoved & ~axesHomed) != 0; +} + // Execute a straight move returning true if an error was written to 'reply' // We have already acquired the movement lock and waited for the previous move to be taken. -bool GCodes::DoStraightMove(GCodeBuffer& gb, const StringRef& reply, bool isCoordinated) +const char* GCodes::DoStraightMove(GCodeBuffer& gb, bool isCoordinated) { // Set up default move parameters moveBuffer.isCoordinated = isCoordinated; @@ -2215,63 +2303,27 @@ bool GCodes::DoStraightMove(GCodeBuffer& gb, const StringRef& reply, bool isCoor moveBuffer.xAxes = DefaultXAxisMapping; moveBuffer.yAxes = DefaultYAxisMapping; } - - if (ival == 1 || ival == 3) - { - for (size_t i = 0; i < numTotalAxes; ++i) - { - if (gb.Seen(axisLetters[i])) - { - SetBit(moveBuffer.endStopsToCheck, i); - } - } - - if (ival == 1) - { - moveBuffer.endStopsToCheck |= HomeAxes; - } - else - { - axesToSenseLength = moveBuffer.endStopsToCheck; - } - } else if (ival == 99) // temporary code to log Z probe change positions { moveBuffer.endStopsToCheck |= LogProbeChanges; } } - // Check for damaging moves on a delta or SCARA printer - const KinematicsType kinType = reprap.GetMove().GetKinematics().GetKinematicsType(); - if (moveBuffer.moveType == 0) + // Check for 'R' parameter to move relative to a restore point + const RestorePoint * rp = nullptr; + if (moveBuffer.moveType == 0 && gb.Seen('R')) { - // Regular move. If it's a delta or SCARA printer, the XYZ axes must be homed first. - constexpr AxesBitmap xyzAxes = LowestNBits<AxesBitmap>(Z_AXIS); - if ((axesHomed & xyzAxes) != xyzAxes && (kinType == KinematicsType::linearDelta || kinType == KinematicsType::scara) && simulationMode == 0) + const uint32_t rParam = gb.GetUIValue(); + if (rParam < ARRAY_SIZE(numberedRestorePoints)) { - // 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. - if (gb.Seen(axisLetters[X_AXIS]) || gb.Seen(axisLetters[Y_AXIS]) || gb.Seen(axisLetters[Z_AXIS])) - { - displayDeltaNotHomedWarning = true; - return false; - } + rp = &numberedRestorePoints[rParam]; } - } - else - { - // Special move. If on a delta, movement must be relative. - if (!gb.MachineState().axesRelative && kinType == KinematicsType::linearDelta) + else { - reply.copy("Attempt to move the motors of a Delta printer to absolute positions"); - return true; + return "G0/G1: bad restore point number"; } } - // Check for 'R' parameter to move relative to a restore point - int rParam = (moveBuffer.moveType == 0 && gb.Seen('R')) ? gb.GetIValue() : 0; - const RestorePoint * const rp = (rParam == 1) ? &pauseRestorePoint : (rParam == 2) ? &toolChangeRestorePoint : nullptr; - #if SUPPORT_IOBITS // Update the iobits parameter if (rp != nullptr) @@ -2290,8 +2342,14 @@ bool GCodes::DoStraightMove(GCodeBuffer& gb, const StringRef& reply, bool isCoor if (moveBuffer.moveType != 0) { + // Special move. If on a delta, movement must be relative. + if (!gb.MachineState().axesRelative && reprap.GetMove().GetKinematics().GetKinematicsType() == KinematicsType::linearDelta) + { + return "G0/G1: attempt to move delta motors to absolute positions"; + } + // This may be a raw motor move, in which case we need the current raw motor positions in moveBuffer.coords. - // If it isn't a raw motor move, it will still be applied without axis or bed transform applies, + // If it isn't a raw motor move, it will still be applied without axis or bed transform applied, // so make sure the initial coordinates don't have those either to avoid unwanted Z movement. reprap.GetMove().GetCurrentUserPosition(moveBuffer.coords, moveBuffer.moveType, reprap.GetCurrentXAxes(), reprap.GetCurrentYAxes()); } @@ -2338,6 +2396,27 @@ bool GCodes::DoStraightMove(GCodeBuffer& gb, const StringRef& reply, bool isCoor // So we no longer do that, and the user must mention any axes that he wants restored e.g. G1 R2 X0 Y0. } + // Check enough axes have been homed + if (moveBuffer.moveType == 0) + { + if (CheckEnoughAxesHomed(axesMentioned)) + { + return "G0/G1: insufficient axes homed"; + } + } + else if (moveBuffer.moveType == 1 || moveBuffer.moveType == 3) + { + moveBuffer.endStopsToCheck |= (axesMentioned & LowestNBits<AxesBitmap>(numTotalAxes)); + if (moveBuffer.moveType == 1) + { + moveBuffer.endStopsToCheck |= HomeAxes; + } + else + { + axesToSenseLength = moveBuffer.endStopsToCheck; + } + } + // Deal with extrusion and feed rate LoadExtrusionAndFeedrateFromGCode(gb, moveBuffer.moveType); @@ -2363,6 +2442,10 @@ bool GCodes::DoStraightMove(GCodeBuffer& gb, const StringRef& reply, bool isCoor } if (limitAxes && reprap.GetMove().GetKinematics().LimitPosition(moveBuffer.coords, numVisibleAxes, effectiveAxesHomed, moveBuffer.isCoordinated)) { + if (machineType != MachineType::fff) + { + return "G0/G1: outside machine limits"; // it's a laser or CNC, so this is a definite error + } ToolOffsetInverseTransform(moveBuffer.coords, currentUserPosition); // make sure the limits are reflected in the user position } @@ -2399,22 +2482,23 @@ bool GCodes::DoStraightMove(GCodeBuffer& gb, const StringRef& reply, bool isCoor doingArcMove = false; FinaliseMove(gb); - return false; + return nullptr; } // Execute an arc move, returning true if it was badly-formed // We already have the movement lock and the last move has gone // Currently, we do not process new babystepping when executing an arc move -bool GCodes::DoArcMove(GCodeBuffer& gb, bool clockwise) +const char* GCodes::DoArcMove(GCodeBuffer& gb, bool clockwise) { // Get the axis parameters. X Y I J are compulsory, Z is optional. - if (!gb.Seen('X')) return true; + const char* const missingParameter = "G2/G3: missing parameter"; + if (!gb.Seen('X')) return missingParameter; const float xParam = gb.GetFValue() * distanceScale; - if (!gb.Seen('Y')) return true; + if (!gb.Seen('Y')) return missingParameter; const float yParam = gb.GetFValue() * distanceScale; - if (!gb.Seen('I')) return true; + if (!gb.Seen('I')) return missingParameter; const float iParam = gb.GetFValue() * distanceScale; - if (!gb.Seen('J')) return true; + if (!gb.Seen('J')) return missingParameter; const float jParam = gb.GetFValue() * distanceScale; memcpy(moveBuffer.initialCoords, moveBuffer.coords, numVisibleAxes * sizeof(moveBuffer.initialCoords[0])); @@ -2436,6 +2520,8 @@ bool GCodes::DoArcMove(GCodeBuffer& gb, bool clockwise) currentUserPosition[Y_AXIS] = yParam; } + AxesBitmap axesMentioned = MakeBitmap<AxesBitmap>(X_AXIS) | MakeBitmap<AxesBitmap>(Y_AXIS); + // Get the optional Z parameter if (gb.Seen('Z')) { @@ -2448,12 +2534,21 @@ bool GCodes::DoArcMove(GCodeBuffer& gb, bool clockwise) { currentUserPosition[Z_AXIS] = zParam; } + axesMentioned |= MakeBitmap<AxesBitmap>(Z_AXIS); + } + + // Check enough axes have been homed + if (CheckEnoughAxesHomed(axesMentioned)) + { + return "G2/G3: insufficient axes homed"; } + // Transform to machine coordinates and check that it is within limits ToolOffsetTransform(currentUserPosition, moveBuffer.coords); // set the final position if (limitAxes && reprap.GetMove().GetKinematics().LimitPosition(moveBuffer.coords, numVisibleAxes, axesHomed, true)) { - ToolOffsetInverseTransform(moveBuffer.coords, currentUserPosition); // make sure the limits are reflected in the user position + // Abandon the move + return "G2/G3: outside machine limits"; } // Compute the angle at which we stop @@ -2491,7 +2586,7 @@ bool GCodes::DoArcMove(GCodeBuffer& gb, bool clockwise) float totalArc = (clockwise) ? arcCurrentAngle - finalTheta : finalTheta - arcCurrentAngle; if (totalArc < 0) { - totalArc += 2 * PI; + totalArc += TwoPi; } // Compute how many segments we need to move, but don't store it yet @@ -2502,11 +2597,13 @@ bool GCodes::DoArcMove(GCodeBuffer& gb, bool clockwise) arcAngleIncrement = -arcAngleIncrement; } + abortedArcMove = false; doingArcMove = true; + gb.SetState(GCodeState::waitingForArcMoveToComplete); FinaliseMove(gb); // debugPrintf("Radius %.2f, initial angle %.1f, increment %.1f, segments %u\n", // arcRadius, arcCurrentAngle * RadiansToDegrees, arcAngleIncrement * RadiansToDegrees, segmentsLeft); - return false; + return nullptr; } // Adjust the move parameters to account for segmentation and/or part of the move having been done already @@ -2602,6 +2699,17 @@ bool GCodes::ReadMove(RawMove& m) --segmentsLeft; return false; } + + // If this is an arc move, we need to limit the end position at each segment. + // This is expensive on a SCARA printer, so we really ought to store theta and phi in the move object for later use. But for now we don't. + if (doingArcMove && limitAxes && reprap.GetMove().GetKinematics().LimitPosition(m.coords, numVisibleAxes, axesHomed, true)) + { + segmentsLeft = 0; + abortedArcMove = true; + doingArcMove = false; + return false; + } + if (segmentsLeftToStartAt == segmentsLeft && firstSegmentFractionToSkip != 0.0) // if this is the segment we are starting at and we need to skip some of it { // Reduce the extrusion by the amount to be skipped @@ -2628,6 +2736,29 @@ void GCodes::ClearMove() moveFractionToSkip = 0.0; } +// Cancel any macro or print in progress +void GCodes::AbortPrint(GCodeBuffer& gb) +{ + gb.AbortFile(); // stop executing any files that this GCodeBuffer is running + if (&gb == fileGCode) // if the current command came from a file being printed + { + reprap.GetHeat().SwitchOffAll(true); // turn all heaters off + switch (machineType) + { + case MachineType::cnc: + platform.SetSpindlePwm(0); + break; + + case MachineType::laser: + platform.SetLaserPwm(0); + break; + + default: + break; + } + } +} + // 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. // Return true if the file was found or it wasn't and we were asked to report that fact. bool GCodes::DoFileMacro(GCodeBuffer& gb, const char* fileName, bool reportMissing, int codeRunning) @@ -3007,7 +3138,7 @@ void GCodes::FinishWrite(GCodeBuffer& gb) } else { - r = (platform.Emulating() == marlin) ? "Done saving file." : ""; + r = (platform.Emulating() == Compatibility::marlin) ? "Done saving file." : ""; } fileBeingWritten = nullptr; gb.SetBinaryWriting(false); @@ -3031,7 +3162,7 @@ void GCodes::WriteGCodeToFile(GCodeBuffer& gb) fileBeingWritten->Close(); fileBeingWritten = nullptr; gb.SetWritingFileDirectory(nullptr); - const char* r = (platform.Emulating() == marlin) ? "Done saving file." : ""; + const char* r = (platform.Emulating() == Compatibility::marlin) ? "Done saving file." : ""; HandleReply(gb, false, r); return; } @@ -3454,23 +3585,23 @@ void GCodes::HandleReply(GCodeBuffer& gb, bool error, const char* reply) // Second UART device, e.g. PanelDue. Do NOT use emulation for this one! if (&gb == auxGCode) { - platform.AppendAuxReply(reply); + platform.AppendAuxReply(reply, reply[0] == '{'); return; } - const Compatibility c = (&gb == serialGCode || &gb == telnetGCode) ? platform.Emulating() : me; + const Compatibility c = (&gb == serialGCode || &gb == telnetGCode) ? platform.Emulating() : Compatibility::me; const MessageType type = gb.GetResponseMessageType(); const char* const response = (gb.GetCommandLetter() == 'M' && gb.GetCommandNumber() == 998) ? "rs " : "ok"; const char* emulationType = nullptr; switch (c) { - case me: - case reprapFirmware: + case Compatibility::me: + case Compatibility::reprapFirmware: platform.MessageF((error) ? (MessageType)(type | ErrorMessageFlag) : type, "%s\n", reply); break; - case marlin: + case Compatibility::marlin: // We don't need to handle M20 here because we always allocate an output buffer for that one if (gb.GetCommandLetter() == 'M' && gb.GetCommandNumber() == 28) { @@ -3494,13 +3625,13 @@ void GCodes::HandleReply(GCodeBuffer& gb, bool error, const char* reply) } break; - case teacup: + case Compatibility::teacup: emulationType = "teacup"; break; - case sprinter: + case Compatibility::sprinter: emulationType = "sprinter"; break; - case repetier: + case Compatibility::repetier: emulationType = "repetier"; break; default: @@ -3524,19 +3655,19 @@ void GCodes::HandleReply(GCodeBuffer& gb, bool error, OutputBuffer *reply) // Second UART device, e.g. dc42's PanelDue. Do NOT use emulation for this one! if (&gb == auxGCode) { - platform.AppendAuxReply(reply); + platform.AppendAuxReply(reply, (*reply)[0] == '{'); return; } - const Compatibility c = (&gb == serialGCode || &gb == telnetGCode) ? platform.Emulating() : me; + const Compatibility c = (&gb == serialGCode || &gb == telnetGCode) ? platform.Emulating() : Compatibility::me; const MessageType type = gb.GetResponseMessageType(); const char* const response = (gb.GetCommandLetter() == 'M' && gb.GetCommandNumber() == 998) ? "rs " : "ok"; const char* emulationType = nullptr; switch (c) { - case me: - case reprapFirmware: + case Compatibility::me: + case Compatibility::reprapFirmware: if (error) { platform.Message(type, "Error: "); @@ -3544,7 +3675,7 @@ void GCodes::HandleReply(GCodeBuffer& gb, bool error, OutputBuffer *reply) platform.Message(type, reply); return; - case marlin: + case Compatibility::marlin: if (gb.GetCommandLetter() =='M' && gb.GetCommandNumber() == 20) { platform.Message(type, "Begin file list\n"); @@ -3590,13 +3721,13 @@ void GCodes::HandleReply(GCodeBuffer& gb, bool error, OutputBuffer *reply) } return; - case teacup: + case Compatibility::teacup: emulationType = "teacup"; break; - case sprinter: + case Compatibility::sprinter: emulationType = "sprinter"; break; - case repetier: + case Compatibility::repetier: emulationType = "repetier"; break; default: @@ -4082,7 +4213,7 @@ void GCodes::StopPrint(bool normalCompletion) } else if (reprap.GetPrintMonitor().IsPrinting()) { - if (platform.Emulating() == marlin) + if (platform.Emulating() == Compatibility::marlin) { // Pronterface expects a "Done printing" message platform.Message(UsbMessage, "Done printing file\n"); @@ -4461,7 +4592,7 @@ void GCodes::CheckReportDue(GCodeBuffer& gb, const StringRef& reply) const { if (now - gb.whenTimerStarted >= 1000) { - if (platform.Emulating() == marlin && (&gb == serialGCode || &gb == telnetGCode)) + if (platform.Emulating() == Compatibility::marlin && (&gb == serialGCode || &gb == telnetGCode)) { // In Marlin emulation mode we should return a standard temperature report every second GenerateTemperatureReport(reply); @@ -4474,7 +4605,7 @@ void GCodes::CheckReportDue(GCodeBuffer& gb, const StringRef& reply) const OutputBuffer * const statusBuf = GenerateJsonStatusResponse(0, -1, ResponseSource::AUX); if (statusBuf != nullptr) { - platform.AppendAuxReply(statusBuf); + platform.AppendAuxReply(statusBuf, true); } } gb.whenTimerStarted = now; diff --git a/src/GCodes/GCodes.h b/src/GCodes/GCodes.h index a7616cd6..be3074f6 100644 --- a/src/GCodes/GCodes.h +++ b/src/GCodes/GCodes.h @@ -240,10 +240,12 @@ private: void HandleReply(GCodeBuffer& gb, bool error, const char *reply); // Handle G-Code replies void HandleReply(GCodeBuffer& gb, bool error, OutputBuffer *reply); - bool DoStraightMove(GCodeBuffer& gb, const StringRef& reply, bool isCoordinated) __attribute__((hot)); // Execute a straight move returning true if an error was written to 'reply' - bool DoArcMove(GCodeBuffer& gb, bool clockwise) // Execute an arc move returning true if it was badly-formed + const char* DoStraightMove(GCodeBuffer& gb, bool isCoordinated) __attribute__((hot)); // Execute a straight move returning any error message + const char* DoArcMove(GCodeBuffer& gb, bool clockwise) // Execute an arc move returning any error message pre(segmentsLeft == 0; resourceOwners[MoveResource] == &gb); void FinaliseMove(const GCodeBuffer& gb); // Adjust the move parameters to account for segmentation and/or part of the move having been done already + bool CheckEnoughAxesHomed(AxesBitmap axesMoved); // Check that enough axes have been homed + void AbortPrint(GCodeBuffer& gb); // Cancel any print in progress GCodeResult DoDwell(GCodeBuffer& gb); // Wait for a bit GCodeResult DoDwellTime(GCodeBuffer& gb, uint32_t dwellMillis); // Really wait for a bit @@ -256,6 +258,7 @@ private: GCodeResult DoDriveMapping(GCodeBuffer& gb, const StringRef& reply); // Deal with a M584 GCodeResult ProbeTool(GCodeBuffer& gb, const StringRef& reply); // Deal with a M585 GCodeResult SetDateTime(GCodeBuffer& gb,const StringRef& reply); // Deal with a M905 + GCodeResult SavePosition(GCodeBuffer& gb,const StringRef& reply); // Deal with G60 bool LoadExtrusionAndFeedrateFromGCode(GCodeBuffer& gb, int moveType); // Set up the extrusion and feed rate of a move for the Move class @@ -401,10 +404,14 @@ private: float arcCurrentAngle; float arcAngleIncrement; bool doingArcMove; + bool abortedArcMove; RestorePoint simulationRestorePoint; // The position and feed rate when we started a simulation - RestorePoint pauseRestorePoint; // The position and feed rate when we paused the print - RestorePoint toolChangeRestorePoint; // The position and feed rate when we freed a tool + + RestorePoint numberedRestorePoints[NumRestorePoints]; // Restore points accessible using the R parameter in the G0/G1 command + RestorePoint& pauseRestorePoint = numberedRestorePoints[1]; // The position and feed rate when we paused the print + RestorePoint& toolChangeRestorePoint = numberedRestorePoints[2]; // The position and feed rate when we freed a tool + size_t numTotalAxes; // How many axes we have size_t numVisibleAxes; // How many axes are visible size_t numExtruders; // How many extruders we have, or may have @@ -514,7 +521,6 @@ private: bool isWaiting; // True if waiting to reach temperature bool cancelWait; // Set true to cancel waiting bool displayNoToolWarning; // True if we need to display a 'no tool selected' warning - bool displayDeltaNotHomedWarning; // True if we need to display a 'attempt to move before homing on a delta printer' message char filamentToLoad[FilamentNameLength]; // Name of the filament being loaded // Standard macro filenames diff --git a/src/GCodes/GCodes2.cpp b/src/GCodes/GCodes2.cpp index a6e1b8ed..c1226920 100644 --- a/src/GCodes/GCodes2.cpp +++ b/src/GCodes/GCodes2.cpp @@ -110,9 +110,16 @@ bool GCodes::HandleGcode(GCodeBuffer& gb, const StringRef& reply) { return false; } - if (DoStraightMove(gb, reply, code == 1)) { - result = GCodeResult::error; + const char* err = DoStraightMove(gb, code == 1); + if (err != nullptr) + { + gb.SetState(GCodeState::waitingForSpecialMoveToComplete, err); // force the user position to be restored + if (&gb == fileGCode) + { + AbortPrint(gb); + } + } } break; @@ -127,10 +134,16 @@ bool GCodes::HandleGcode(GCodeBuffer& gb, const StringRef& reply) { return false; } - if (DoArcMove(gb, code == 2)) { - reply.copy("Invalid arc parameters"); - result = GCodeResult::error; + const char* err = DoArcMove(gb, code == 2); + if (err != nullptr) + { + gb.SetState(GCodeState::waitingForSpecialMoveToComplete, err); // force the user position to be restored + if (&gb == fileGCode) + { + AbortPrint(gb); + } + } } break; @@ -283,6 +296,10 @@ bool GCodes::HandleGcode(GCodeBuffer& gb, const StringRef& reply) break; #endif + case 60: // Save position + result = SavePosition(gb, reply); + break; + case 90: // Absolute coordinates gb.MachineState().axesRelative = false; break; @@ -518,12 +535,12 @@ bool GCodes::HandleMcode(GCodeBuffer& gb, const StringRef& reply) // If we are emulating RepRap then we print "GCode files:\n" at the start, otherwise we don't. // If we are emulating Marlin and the code came via the serial/USB interface, then we don't put quotes around the names and we separate them with newline; // otherwise we put quotes around them and separate them with comma. - if (platform.Emulating() == me || platform.Emulating() == reprapFirmware) + if (platform.Emulating() == Compatibility::me || platform.Emulating() == Compatibility::reprapFirmware) { fileResponse->copy("GCode files:\n"); } - bool encapsulateList = ((&gb != serialGCode && &gb != telnetGCode) || platform.Emulating() != marlin); + bool encapsulateList = ((&gb != serialGCode && &gb != telnetGCode) || platform.Emulating() != Compatibility::marlin); FileInfo fileInfo; if (platform.GetMassStorage()->FindFirst(dir.Pointer(), fileInfo)) { @@ -599,7 +616,7 @@ bool GCodes::HandleMcode(GCodeBuffer& gb, const StringRef& reply) if (QueueFileToPrint(filename.Pointer(), reply)) { reprap.GetPrintMonitor().StartingPrint(filename.Pointer()); - if (platform.Emulating() == marlin && (&gb == serialGCode || &gb == telnetGCode)) + if (platform.Emulating() == Compatibility::marlin && (&gb == serialGCode || &gb == telnetGCode)) { reply.copy("File opened\nFile selected"); } @@ -699,7 +716,7 @@ bool GCodes::HandleMcode(GCodeBuffer& gb, const StringRef& reply) } else { - if (!LockMovement(gb)) // lock movement before calling DoPause + if (!LockMovement(gb)) // lock movement before calling DoPause { return false; } @@ -945,13 +962,14 @@ bool GCodes::HandleMcode(GCodeBuffer& gb, const StringRef& reply) gb.TryGetIValue('S', format, dummy); uint64_t capacity, freeSpace; uint32_t speed; - const MassStorage::InfoResult res = platform.GetMassStorage()->GetCardInfo(slot, capacity, freeSpace, speed); + uint32_t clSize; + const MassStorage::InfoResult res = platform.GetMassStorage()->GetCardInfo(slot, capacity, freeSpace, speed, clSize); if (format == 2) { reply.printf("{\"SDinfo\":{\"slot\":%" PRIu32 ",\"present\":", slot); if (res == MassStorage::InfoResult::ok) { - reply.catf("1,\"capacity\":%" PRIu64 ",\"free\":%" PRIu64 ",\"speed\":%" PRIu32 "}}", capacity, freeSpace, speed); + reply.catf("1,\"capacity\":%" PRIu64 ",\"free\":%" PRIu64 ",\"speed\":%" PRIu32 ",\"clsize\":%" PRIu32 "}}", capacity, freeSpace, speed, clSize); } else { @@ -974,8 +992,16 @@ bool GCodes::HandleMcode(GCodeBuffer& gb, const StringRef& reply) break; case MassStorage::InfoResult::ok: - reply.printf("SD card in slot %" PRIu32 ": capacity %.2fGb, free space %.2fGb, speed %.2fMBytes/sec", + reply.printf("SD card in slot %" PRIu32 ": capacity %.2fGb, free space %.2fGb, speed %.2fMBytes/sec, cluster size ", slot, (double)capacity/(1000*1000*1000), (double)freeSpace/(1000*1000*1000), (double)speed/(1000*1000)); + if (clSize < 1024) + { + reply.catf("%" PRIu32 " bytes", clSize); + } + else + { + reply.catf("%" PRIu32 "kb", clSize/1024); + } break; } } @@ -1357,9 +1383,10 @@ bool GCodes::HandleMcode(GCodeBuffer& gb, const StringRef& reply) break; case 116: // Wait for set temperatures + if (!cancelWait) { bool seen = false; - if (!cancelWait && gb.Seen('P')) + if (gb.Seen('P')) { // Wait for the heaters associated with the specified tool to be ready int toolNumber = gb.GetIValue(); @@ -1373,7 +1400,7 @@ bool GCodes::HandleMcode(GCodeBuffer& gb, const StringRef& reply) seen = true; } - if (!cancelWait && gb.Seen('H')) + if (gb.Seen('H')) { // Wait for specified heaters to be ready uint32_t heaters[Heaters]; @@ -1392,7 +1419,7 @@ bool GCodes::HandleMcode(GCodeBuffer& gb, const StringRef& reply) seen = true; } - if (!cancelWait && gb.Seen('C')) + if (gb.Seen('C')) { // Wait for specified chamber(s) to be ready uint32_t chamberIndices[NumChamberHeaters]; @@ -1434,16 +1461,16 @@ bool GCodes::HandleMcode(GCodeBuffer& gb, const StringRef& reply) } // Wait for all heaters except chamber(s) to be ready - if (!seen && !cancelWait && !reprap.GetHeat().AllHeatersAtSetTemperatures(true)) + if (!seen && !reprap.GetHeat().AllHeatersAtSetTemperatures(true)) { CheckReportDue(gb, reply); // check whether we need to send a temperature or status report isWaiting = true; return false; } - - // If we get here, there is nothing more to wait for - cancelWait = isWaiting = false; } + + // If we get here, there is nothing more to wait for + cancelWait = isWaiting = false; break; case 117: // Display message @@ -1454,6 +1481,47 @@ bool GCodes::HandleMcode(GCodeBuffer& gb, const StringRef& reply) } break; + case 118: // Echo message on host + { + MessageType type = GenericMessage; + if (gb.Seen('P')) + { + switch (gb.GetIValue()) + { + case 0: // Generic (default) + // no need to set it twice + break; + case 1: // USB + type = UsbMessage; + break; + case 2: // UART port + type = DirectLcdMessage; + break; + case 3: // HTTP + type = HttpMessage; + break; + case 4: // Telnet + type = TelnetMessage; + break; + default: + reply.printf("Invalid message type: %d", type); + result = GCodeResult::error; + break; + } + } + + if (result != GCodeResult::error) + { + String<GCODE_LENGTH> message; + if (gb.Seen(('S'))) + { + gb.GetQuotedString(message.GetRef()); + platform.Message(type, message.c_str()); + } + } + } + break; + case 119: reply.copy("Endstops - "); for (size_t axis = 0; axis < numTotalAxes; axis++) @@ -1539,20 +1607,23 @@ bool GCodes::HandleMcode(GCodeBuffer& gb, const StringRef& reply) } const int8_t currentHeater = (code == 141) ? heat.GetChamberHeater(index) : heat.GetBedHeater(index); - const char* heaterName = (code == 141) ? "chamber" : "bed"; + const char* const heaterName = (code == 141) ? "chamber" : "bed"; // Active temperature if (gb.Seen('S')) { seen = true; + const float temperature = gb.GetFValue(); if (currentHeater < 0) { - reply.printf("No %s heater has been configured for slot %d", heaterName, index); - result = GCodeResult::error; + if (temperature > 0.0) // turning off a non-existent bed or chamber heater is not an error + { + reply.printf("No %s heater has been configured for slot %d", heaterName, index); + result = GCodeResult::error; + } } else { - const float temperature = gb.GetFValue(); if (temperature < NEARLY_ABS_ZERO) { heat.SwitchOff(currentHeater); @@ -1583,7 +1654,7 @@ bool GCodes::HandleMcode(GCodeBuffer& gb, const StringRef& reply) { if (currentHeater < 0) { - reply.printf("No %s heater has been configuredt for slot %d", heaterName, index); + reply.printf("No %s heater has been configured for slot %d", heaterName, index); } else { @@ -1672,7 +1743,7 @@ bool GCodes::HandleMcode(GCodeBuffer& gb, const StringRef& reply) for (size_t i = 0; i < len; ++i) { const float d = diameters[i]; - volumetricExtrusionFactors[i] = (d <= 0.0) ? 1.0 : 4.0/(fsquare(d) * PI); + volumetricExtrusionFactors[i] = (d <= 0.0) ? 1.0 : 4.0/(fsquare(d) * Pi); } gb.MachineState().volumetricExtrusion = (diameters[0] > 0.0); } @@ -1692,7 +1763,7 @@ bool GCodes::HandleMcode(GCodeBuffer& gb, const StringRef& reply) } else { - reply.catf(" %.03f", (double)(2.0/sqrtf(vef * PI))); + reply.catf(" %.03f", (double)(2.0/sqrtf(vef * Pi))); } } } @@ -1785,7 +1856,7 @@ bool GCodes::HandleMcode(GCodeBuffer& gb, const StringRef& reply) case 204: // Set max travel and printing accelerations { bool seen = false; - if (gb.Seen('S') && platform.Emulating() == marlin) + if (gb.Seen('S') && platform.Emulating() == Compatibility::marlin) { // For backwards compatibility e.g. with Cura, set both accelerations as Marlin does. const float acc = gb.GetFValue(); @@ -2434,7 +2505,8 @@ bool GCodes::HandleMcode(GCodeBuffer& gb, const StringRef& reply) { lp = NoLogicalPin; } - if (platform.SetLaserPin((LogicalPin)lp)) + const bool invert = (gb.Seen('I') && gb.GetIValue() > 0); + if (platform.SetLaserPin((LogicalPin)lp, invert)) { reply.copy("Laser mode selected"); } @@ -2469,7 +2541,8 @@ bool GCodes::HandleMcode(GCodeBuffer& gb, const StringRef& reply) { pins[1] = NoLogicalPin; } - if (platform.SetSpindlePins(pins[0], pins[1])) + const bool invert = (gb.Seen('I') && gb.GetIValue() > 0); + if (platform.SetSpindlePins(pins[0], pins[1], invert)) { reply.copy("CNC mode selected"); } @@ -2717,29 +2790,29 @@ bool GCodes::HandleMcode(GCodeBuffer& gb, const StringRef& reply) reply.copy("Emulating "); switch (platform.Emulating()) { - case me: - case reprapFirmware: + case Compatibility::me: + case Compatibility::reprapFirmware: reply.cat("RepRap Firmware (i.e. in native mode)"); break; - case marlin: + case Compatibility::marlin: reply.cat("Marlin"); break; - case teacup: + case Compatibility::teacup: reply.cat("Teacup"); break; - case sprinter: + case Compatibility::sprinter: reply.cat("Sprinter"); break; - case repetier: + case Compatibility::repetier: reply.cat("Repetier"); break; default: - reply.catf("Unknown: (%d)", platform.Emulating()); + reply.catf("Unknown: (%u)", (unsigned int)platform.Emulating()); } } break; @@ -2748,11 +2821,14 @@ bool GCodes::HandleMcode(GCodeBuffer& gb, const StringRef& reply) if (gb.Seen('S')) { const float value = gb.GetFValue(); - for (size_t axis = 0; axis <= Z_AXIS; axis++) + if (value >= 10.0) // avoid divide by zero and silly results { - if (gb.Seen(axisLetters[axis])) + for (size_t axis = 0; axis <= Z_AXIS; axis++) { - reprap.GetMove().SetAxisCompensation(axis, gb.GetFValue() / value); + if (gb.Seen(axisLetters[axis])) + { + reprap.GetMove().SetAxisCompensation(axis, gb.GetFValue() / value); + } } } } @@ -3028,7 +3104,8 @@ bool GCodes::HandleMcode(GCodeBuffer& gb, const StringRef& reply) if (gb.Seen('P')) { const int pwmPin = gb.GetIValue(); - if (!platform.SetExtrusionAncilliaryPwmPin(pwmPin)) + const bool invert = (gb.Seen('I') && gb.GetIValue() > 0); + if (!platform.SetExtrusionAncilliaryPwmPin(pwmPin, invert)) { reply.printf("Logical pin %d is already in use or not available for use by M571", pwmPin); break; // don't process 'S' parameter if the pin was wrong @@ -3046,10 +3123,13 @@ bool GCodes::HandleMcode(GCodeBuffer& gb, const StringRef& reply) } if (!seen) { - reply.printf("Extrusion ancillary PWM %.3f at %.1fHz on pin %u", + bool invert; + const LogicalPin pin = platform.GetExtrusionAncilliaryPwmPin(invert); + reply.printf("Extrusion ancillary PWM %.3f at %.1fHz on pin %u, %s", (double)platform.GetExtrusionAncilliaryPwmValue(), (double)platform.GetExtrusionAncilliaryPwmFrequency(), - platform.GetExtrusionAncilliaryPwmPin()); + (unsigned int)pin, + (invert) ? "inverted" : "not inverted"); } } break; @@ -3168,6 +3248,7 @@ bool GCodes::HandleMcode(GCodeBuffer& gb, const StringRef& reply) break; case 1: auxGCode->SetCommsProperties(val); + platform.SetAuxDetected(); break; default: break; @@ -3949,7 +4030,7 @@ bool GCodes::HandleMcode(GCodeBuffer& gb, const StringRef& reply) break; #endif - // 917 set standstill current reduction not yet supported + // For case 917, see 906 #if SUPPORT_12864_LCD case 918: // Configure direct-connect display diff --git a/src/GCodes/GCodes3.cpp b/src/GCodes/GCodes3.cpp index 6251341c..4fee02ae 100644 --- a/src/GCodes/GCodes3.cpp +++ b/src/GCodes/GCodes3.cpp @@ -99,6 +99,20 @@ GCodeResult GCodes::SetPrintZProbe(GCodeBuffer& gb, const StringRef& reply) return GCodeResult::ok; } +// Deal with G60 +GCodeResult GCodes::SavePosition(GCodeBuffer& gb,const StringRef& reply) +{ + const uint32_t sParam = (gb.Seen('S')) ? gb.GetUIValue() : 0; + if (sParam < ARRAY_SIZE(numberedRestorePoints)) + { + SavePosition(numberedRestorePoints[sParam], gb); + return GCodeResult::ok; + } + + reply.copy("Bad restore point number"); + return GCodeResult::error; +} + // This handles G92. Return true if completed, false if it needs to be called again. GCodeResult GCodes::SetPositions(GCodeBuffer& gb) { diff --git a/src/Heating/Sensors/DhtSensor.cpp b/src/Heating/Sensors/DhtSensor.cpp index 2349969b..49e99d65 100644 --- a/src/Heating/Sensors/DhtSensor.cpp +++ b/src/Heating/Sensors/DhtSensor.cpp @@ -188,7 +188,7 @@ void DhtDataTransition(CallbackParameter) // due to the fact that this messes with the stepping ISR numPulses = 0; lastPulseTime = 0; - attachInterrupt(DhtDataPin, DhtDataTransition, CHANGE, nullptr); + attachInterrupt(DhtDataPin, DhtDataTransition, INTERRUPT_MODE_CHANGE, nullptr); // Wait for the next operation to complete lastOperationTime = millis(); diff --git a/src/IoPorts.cpp b/src/IoPorts.cpp index 097cdc7c..5ec57499 100644 --- a/src/IoPorts.cpp +++ b/src/IoPorts.cpp @@ -27,8 +27,9 @@ void IoPort::Clear() invert = false; } -bool IoPort::Set(LogicalPin lp, PinAccess access) +bool IoPort::Set(LogicalPin lp, PinAccess access, bool pInvert) { + invert = pInvert; const bool ret = reprap.GetPlatform().GetFirmwarePin(lp, access, pin, invert); if (!ret) { diff --git a/src/IoPorts.h b/src/IoPorts.h index c6f3a69f..f4e5eb20 100644 --- a/src/IoPorts.h +++ b/src/IoPorts.h @@ -29,9 +29,10 @@ class IoPort public: IoPort(); void Clear(); - bool Set(LogicalPin lp, PinAccess access); + bool Set(LogicalPin lp, PinAccess access, bool pInvert); LogicalPin GetLogicalPin() const { return logicalPort; } + LogicalPin GetLogicalPin(bool& pInvert) const { pInvert = invert; return logicalPort; } void WriteDigital(bool high) const { if (pin != NoPin) { WriteDigital(pin, (invert) ? !high : high); } } // Low level port access diff --git a/src/Libraries/Fatfs/conf_fatfs.h b/src/Libraries/Fatfs/conf_fatfs.h index ec780a03..a41065fe 100644 --- a/src/Libraries/Fatfs/conf_fatfs.h +++ b/src/Libraries/Fatfs/conf_fatfs.h @@ -94,7 +94,7 @@ /* To enable f_forward function, set _USE_FORWARD to 1 and set _FS_TINY to 1. */ -#define _USE_FASTSEEK 0 /* 0:Disable or 1:Enable */ +#define _USE_FASTSEEK 1 /* 0:Disable or 1:Enable */ /* To enable fast seek feature, set _USE_FASTSEEK to 1. */ diff --git a/src/Libraries/Fatfs/ff.c b/src/Libraries/Fatfs/ff.c index 881f546b..67a70915 100644 --- a/src/Libraries/Fatfs/ff.c +++ b/src/Libraries/Fatfs/ff.c @@ -1070,7 +1070,7 @@ DWORD clmt_clust ( /* <2:Error, >=2:Cluster number */ tbl = fp->cltbl + 1; /* Top of CLMT */ cl = ofs / SS(fp->fs) / fp->fs->csize; /* Cluster order from top of the file */ for (;;) { - ncl = *tbl++; /* Number of cluters in the fragment */ + ncl = *tbl++; /* Number of clusters in the fragment */ if (!ncl) return 0; /* End of table? (error) */ if (cl < ncl) break; /* In this fragment? */ cl -= ncl; tbl++; /* Next fragment */ diff --git a/src/MessageType.h b/src/MessageType.h index cd20f104..0f6a4d29 100644 --- a/src/MessageType.h +++ b/src/MessageType.h @@ -15,7 +15,7 @@ enum MessageType : uint16_t { // Destinations UsbMessage = 0x01, // A message that is to be sent in non-blocking mode to the host via USB - BlockingUsbMessage = 0x02, // A message to be sent ot USB in blocking mode + BlockingUsbMessage = 0x02, // A message to be sent to USB in blocking mode LcdMessage = 0x04, // A message that is to be sent to the panel ImmediateLcdMessage = 0x08, // A message to be sent to LCD in immediate mode HttpMessage = 0x10, // A message that is to be sent to the web (HTTP) @@ -23,23 +23,21 @@ enum MessageType : uint16_t AuxMessage = 0x40, // A message that is to be sent to the second auxiliary device LogMessage = 0x80, // A message to be written to the log file - // Special indicators. These are not processed when calling the version of Platform::Message that takes an OutputBuffer. + // Special indicators. The first two are not processed when calling the version of Platform::Message that takes an OutputBuffer. ErrorMessageFlag = 0x100, // This is an error message WarningMessageFlag = 0x200, // This is a warning message + RawMessageFlag = 0x400, // Do not encapsulate this message // Common combinations DebugMessage = BlockingUsbMessage, // A debug message to send in blocking mode to USB GenericMessage = UsbMessage | LcdMessage | HttpMessage | TelnetMessage, // A message that is to be sent to the web, Telnet, USB and panel LoggedGenericMessage = GenericMessage | LogMessage, // A GenericMessage that is also logged - ErrorMessage = GenericMessage | LogMessage | ErrorMessageFlag, // An error message + DirectLcdMessage = LcdMessage | RawMessageFlag, // Direct message to LCD + ErrorMessage = GenericMessage | LogMessage | ErrorMessageFlag, // An error message WarningMessage = GenericMessage | LogMessage | WarningMessageFlag, // A warning message FirmwareUpdateMessage = UsbMessage | ImmediateLcdMessage, // A message that conveys progress of a firmware update FirmwareUpdateErrorMessage = FirmwareUpdateMessage | ErrorMessageFlag, // A message that reports an error during a firmware update NetworkInfoMessage = UsbMessage | LcdMessage | LogMessage, // A message that conveys information about the state of the network interface - - // Masks - MessageDestinationMask = 0x00FF, - MessageFlagsMask = 0x00F0 }; inline MessageType AddError(MessageType mt) diff --git a/src/Movement/DDA.cpp b/src/Movement/DDA.cpp index 54fe9e95..a0bf5aab 100644 --- a/src/Movement/DDA.cpp +++ b/src/Movement/DDA.cpp @@ -460,8 +460,8 @@ bool DDA::Init(GCodes::RawMove &nextMove, bool doMotorMapping) } // Don't use the constrain function in the following, because if we have a very small XY movement and a lot of extrusion, we may have to make the - // speed lower than the 0.5mm/sec minimum. We must apply the minimum speed first and then limit it if necessary after that. - requestedSpeed = min<float>(max<float>(reqSpeed, 0.5), VectorBoxIntersection(normalisedDirectionVector, reprap.GetPlatform().MaxFeedrates(), DRIVES)); + // speed lower than MinimumMovementSpeed. We must apply the minimum speed first and then limit it if necessary after that. + requestedSpeed = min<float>(max<float>(reqSpeed, MinimumMovementSpeed), VectorBoxIntersection(normalisedDirectionVector, reprap.GetPlatform().MaxFeedrates(), DRIVES)); // On a Cartesian printer, it is OK to limit the X and Y speeds and accelerations independently, and in consequence to allow greater values // for diagonal moves. On a delta, this is not OK and any movement in the XY plane should be limited to the X/Y axis values, which we assume to be equal. @@ -471,7 +471,7 @@ bool DDA::Init(GCodes::RawMove &nextMove, bool doMotorMapping) } // 7. Calculate the provisional accelerate and decelerate distances and the top speed - endSpeed = 0.0; // until the next move asks us to adjust it + endSpeed = 0.0; // until the next move asks us to adjust it if (prev->state != provisional || isPrintingMove != prev->isPrintingMove || xyMoving != prev->xyMoving) { @@ -1386,7 +1386,7 @@ pre(state == frozen) { const size_t drive = pdm->drive; reprap.GetPlatform().SetDirection(drive, pdm->direction); - if (drive >= numAxes && drive < DRIVES) + if (drive >= numAxes) { if (pdm->direction == FORWARDS) { @@ -1481,24 +1481,30 @@ bool DDA::Step() //if (t3 < minCalcTime) minCalcTime = t3; } - // 3. Step the drivers - if ((driversStepping & platform.GetSlowDrivers()) != 0) + if ((driversStepping & platform.GetSlowDrivers()) == 0) // if not using any external drivers { - while (Platform::GetInterruptClocks() - lastStepPulseTime < platform.GetSlowDriverClocks()) {} + // 3. Step the drivers Platform::StepDriversHigh(driversStepping); // generate the steps - lastStepPulseTime = Platform::GetInterruptClocks(); } else { + // 3. Step the drivers + while (Platform::GetInterruptClocks() - lastStepPulseTime < platform.GetSlowDriverClocks()) {} Platform::StepDriversHigh(driversStepping); // generate the steps + lastStepPulseTime = Platform::GetInterruptClocks(); + + // 3a. Reset all step pins low. Do this now because some external drivers don't like the direction pins being changed before the end of the step pulse. + while (Platform::GetInterruptClocks() - lastStepPulseTime < platform.GetSlowDriverClocks()) {} + Platform::StepDriversLow(); // set all step pins low + lastStepPulseTime = Platform::GetInterruptClocks(); } // 4. Remove those drives from the list, calculate the next step times, update the direction pins where necessary, - // and re-insert them so as to keep the list in step-time order. We assume that meeting the direction pin hold time - // is not a problem for any driver type. This is not necessarily true. - DriveMovement *dmToInsert = firstDM; // head of the chain we need to re-insert - firstDM = dm; // remove the chain from the list - while (dmToInsert != dm) // note that both of these may be nullptr + // and re-insert them so as to keep the list in step-time order. + // Note that the call to CalcNextStepTime may change the state of Direction pin. + DriveMovement *dmToInsert = firstDM; // head of the chain we need to re-insert + firstDM = dm; // remove the chain from the list + while (dmToInsert != dm) // note that both of these may be nullptr { const bool hasMoreSteps = (isDeltaMovement && dmToInsert->drive < DELTA_AXES) ? dmToInsert->CalcNextStepTimeDelta(*this, true) @@ -1511,17 +1517,8 @@ bool DDA::Step() dmToInsert = nextToInsert; } - // 5. Reset all step pins low - if ((driversStepping & platform.GetSlowDrivers()) != 0) - { - while (Platform::GetInterruptClocks() - lastStepPulseTime < platform.GetSlowDriverClocks()) {} - Platform::StepDriversLow(); // set all step pins low - lastStepPulseTime = Platform::GetInterruptClocks(); - } - else - { - Platform::StepDriversLow(); // set all step pins low - } + // 5. Reset all step pins low. We already did this if we are using any external drivers, but doing it again does no harm. + Platform::StepDriversLow(); // set all step pins low // 6. Check for move completed if (firstDM == nullptr) diff --git a/src/Movement/Kinematics/ZLeadscrewKinematics.cpp b/src/Movement/Kinematics/ZLeadscrewKinematics.cpp index 1e263e8b..9be14ec1 100644 --- a/src/Movement/Kinematics/ZLeadscrewKinematics.cpp +++ b/src/Movement/Kinematics/ZLeadscrewKinematics.cpp @@ -13,12 +13,12 @@ const float M3ScrewPitch = 0.5; ZLeadscrewKinematics::ZLeadscrewKinematics(KinematicsType k) - : Kinematics(k, -1.0, 0.0, true), numLeadscrews(0), maxCorrection(1.0), screwPitch(M3ScrewPitch) + : Kinematics(k, -1.0, 0.0, true), numLeadscrews(0), correctionFactor(1.0), maxCorrection(1.0), screwPitch(M3ScrewPitch) { } ZLeadscrewKinematics::ZLeadscrewKinematics(KinematicsType k, float segsPerSecond, float minSegLength, bool doUseRawG0) - : Kinematics(k, segsPerSecond, minSegLength, doUseRawG0), numLeadscrews(0), maxCorrection(1.0), screwPitch(M3ScrewPitch) + : Kinematics(k, segsPerSecond, minSegLength, doUseRawG0), numLeadscrews(0), correctionFactor(1.0), maxCorrection(1.0), screwPitch(M3ScrewPitch) { } @@ -43,11 +43,10 @@ bool ZLeadscrewKinematics::Configure(unsigned int mCode, GCodeBuffer& gb, const seenY = true; } - bool seenS = false; - gb.TryGetFValue('S', maxCorrection, seenS); - - bool seenP = false; - gb.TryGetFValue('P', screwPitch, seenP); + bool seenPFS = false; + gb.TryGetFValue('S', maxCorrection, seenPFS); + gb.TryGetFValue('P', screwPitch, seenPFS); + gb.TryGetFValue('F', correctionFactor, seenPFS); if (seenX && seenY && xSize == ySize) { @@ -62,7 +61,7 @@ bool ZLeadscrewKinematics::Configure(unsigned int mCode, GCodeBuffer& gb, const } // If no parameters provided so just report the existing setup - if (seenS || seenP) + if (seenPFS) { return true; // just changed the maximum correction or screw pitch } @@ -77,7 +76,7 @@ bool ZLeadscrewKinematics::Configure(unsigned int mCode, GCodeBuffer& gb, const { reply.catf(" (%.1f,%.1f)", (double)leadscrewX[i], (double)leadscrewY[i]); } - reply.catf(", maximum correction %.02fmm, manual adjusting screw pitch %.02fmm", (double)maxCorrection, (double)screwPitch); + reply.catf(", factor %.02f, maximum correction %.02fmm, manual adjusting screw pitch %.02fmm", (double)correctionFactor, (double)maxCorrection, (double)screwPitch); } return false; } @@ -262,9 +261,13 @@ bool ZLeadscrewKinematics::DoAutoCalibration(size_t numFactors, const RandomProb { haveNaN = true; } - else if (fabsf(solution[i]) > maxCorrection) + else { - haveLargeCorrection = true; + solution[i] *= (floatc_t)correctionFactor; + if (fabsf(solution[i]) > maxCorrection) + { + haveLargeCorrection = true; + } } } diff --git a/src/Movement/Kinematics/ZLeadscrewKinematics.h b/src/Movement/Kinematics/ZLeadscrewKinematics.h index 206a95a5..21e82041 100644 --- a/src/Movement/Kinematics/ZLeadscrewKinematics.h +++ b/src/Movement/Kinematics/ZLeadscrewKinematics.h @@ -30,6 +30,7 @@ private: unsigned int numLeadscrews; float leadscrewX[MaxLeadscrews], leadscrewY[MaxLeadscrews]; + float correctionFactor; float maxCorrection; float screwPitch; }; diff --git a/src/Networking/ESP8266WiFi/WiFiInterface.cpp b/src/Networking/ESP8266WiFi/WiFiInterface.cpp index 564637d2..3b8bfaa1 100644 --- a/src/Networking/ESP8266WiFi/WiFiInterface.cpp +++ b/src/Networking/ESP8266WiFi/WiFiInterface.cpp @@ -121,7 +121,7 @@ static void EspTransferRequestIsr(CallbackParameter) static inline void EnableEspInterrupt() { - attachInterrupt(EspDataReadyPin, EspTransferRequestIsr, RISING, nullptr); + attachInterrupt(EspDataReadyPin, EspTransferRequestIsr, INTERRUPT_MODE_RISING, nullptr); } static inline void DisableEspInterrupt() @@ -673,12 +673,10 @@ void WiFiInterface::Spin(bool full) // Check for debug info received from the WiFi module if (debugPrintPending) { -#if 0 if (reprap.Debug(moduleWiFi)) { debugPrintf("WiFi: %s\n", debugMessageBuffer.Pointer()); } -#endif debugMessageBuffer.Clear(); debugPrintPending = false; } @@ -1197,11 +1195,6 @@ void WiFiInterface::TerminateDataPort() } } -void WiFiInterface::DataPortClosing() -{ - StopListening(ftpDataPort); -} - #if USE_PDC static Pdc *spi_pdc; #endif diff --git a/src/Networking/ESP8266WiFi/WiFiInterface.h b/src/Networking/ESP8266WiFi/WiFiInterface.h index 35561f7c..a77573a2 100644 --- a/src/Networking/ESP8266WiFi/WiFiInterface.h +++ b/src/Networking/ESP8266WiFi/WiFiInterface.h @@ -44,8 +44,8 @@ public: void Exit() override; void Spin(bool full) override; void Diagnostics(MessageType mtype) override; - void Start() override; - void Stop() override; + void Start(); + void Stop(); GCodeResult EnableInterface(int mode, const StringRef& ssid, const StringRef& reply) override; // enable or disable the network GCodeResult EnableProtocol(NetworkProtocol protocol, int port, int secure, const StringRef& reply) override; @@ -65,7 +65,6 @@ public: void OpenDataPort(Port port) override; void TerminateDataPort() override; - void DataPortClosing() override; // The remaining functions are specific to the WiFi version GCodeResult HandleWiFiCode(int mcode, GCodeBuffer &gb, const StringRef& reply, OutputBuffer*& longReply); diff --git a/src/Networking/FtpResponder.cpp b/src/Networking/FtpResponder.cpp index 42086913..635bf362 100644 --- a/src/Networking/FtpResponder.cpp +++ b/src/Networking/FtpResponder.cpp @@ -128,8 +128,6 @@ bool FtpResponder::Spin() outBuf->copy("226 Transfer complete.\r\n"); } Commit(ResponderState::reading); - - // Close the data port again CloseDataPort(); } else @@ -891,7 +889,6 @@ void FtpResponder::CloseDataPort() if (dataSocket != nullptr) { - dataSocket->GetInterface()->DataPortClosing(); dataSocket->Close(); // close it gracefully dataSocket = nullptr; } diff --git a/src/Networking/LwipEthernet/LwipEthernetInterface.cpp b/src/Networking/LwipEthernet/LwipEthernetInterface.cpp index 9d129ecd..c203cf28 100644 --- a/src/Networking/LwipEthernet/LwipEthernetInterface.cpp +++ b/src/Networking/LwipEthernet/LwipEthernetInterface.cpp @@ -657,17 +657,6 @@ void LwipEthernetInterface::TerminateDataPort() } } -// Stop listening on a port -void LwipEthernetInterface::DataPortClosing() -{ - // This is currently called only for the FTP data port - if (listeningPcbs[NumProtocols] != nullptr) - { - tcp_close(listeningPcbs[NumProtocols]); - listeningPcbs[NumProtocols] = nullptr; - } -} - void LwipEthernetInterface::InitSockets() { for (size_t i = 0; i < NumProtocols; ++i) diff --git a/src/Networking/LwipEthernet/LwipEthernetInterface.h b/src/Networking/LwipEthernet/LwipEthernetInterface.h index c816e573..6acdfae1 100644 --- a/src/Networking/LwipEthernet/LwipEthernetInterface.h +++ b/src/Networking/LwipEthernet/LwipEthernetInterface.h @@ -36,8 +36,6 @@ public: void Spin(bool full) override; void Interrupt() override; void Diagnostics(MessageType mtype) override; - void Start() override; - void Stop() override; GCodeResult EnableInterface(int mode, const StringRef& ssid, const StringRef& reply) override; // enable or disable the network GCodeResult EnableProtocol(NetworkProtocol protocol, int port, int secure, const StringRef& reply) override; @@ -60,7 +58,6 @@ public: void OpenDataPort(Port port) override; void TerminateDataPort() override; - void DataPortClosing() override; private: enum class NetworkState @@ -73,6 +70,8 @@ private: active // network running }; + void Start(); + void Stop(); void InitSockets(); void TerminateSockets(); diff --git a/src/Networking/Network.cpp b/src/Networking/Network.cpp index 3dd42c52..18586b72 100644 --- a/src/Networking/Network.cpp +++ b/src/Networking/Network.cpp @@ -228,31 +228,6 @@ GCodeResult Network::GetNetworkState(unsigned int interface, const StringRef& re return GCodeResult::error; } -// Start up the network -void Network::Start(unsigned int interface) -{ - if (interface < NumNetworkInterfaces) - { - interfaces[interface]->Start(); - } -} - -// Stop the network -void Network::Stop(unsigned int interface) -{ -#if 0 // chrishamm: I wonder if this is actually needed - when sockets are disabled their state changes anyway - for (NetworkResponder *r = responders; r != nullptr; r = r->GetNext()) - { - r->Terminate(AnyProtocol); - } -#endif - - if (interface < NumNetworkInterfaces && interfaces[interface] != nullptr) - { - interfaces[interface]->Stop(); - } -} - bool Network::IsWiFiInterface(unsigned int interface) const { return interface < NumNetworkInterfaces && interfaces[interface]->IsWiFiInterface(); diff --git a/src/Networking/Network.h b/src/Networking/Network.h index 6cd2d268..308ec272 100644 --- a/src/Networking/Network.h +++ b/src/Networking/Network.h @@ -45,9 +45,6 @@ public: void Interrupt(); void Diagnostics(MessageType mtype); bool InNetworkStack() const; - - void Start(unsigned int interface); - void Stop(unsigned int interface); bool IsWiFiInterface(unsigned int interface) const; GCodeResult EnableInterface(unsigned int interface, int mode, const StringRef& ssid, const StringRef& reply); diff --git a/src/Networking/NetworkInterface.h b/src/Networking/NetworkInterface.h index a292d34b..6e10ea4f 100644 --- a/src/Networking/NetworkInterface.h +++ b/src/Networking/NetworkInterface.h @@ -20,8 +20,6 @@ public: virtual void Spin(bool full) = 0; virtual void Interrupt() { }; virtual void Diagnostics(MessageType mtype) = 0; - virtual void Start() = 0; - virtual void Stop() = 0; virtual GCodeResult EnableInterface(int mode, const StringRef& ssid, const StringRef& reply) = 0; virtual GCodeResult GetNetworkState(const StringRef& reply) = 0; @@ -42,7 +40,6 @@ public: virtual void OpenDataPort(Port port) = 0; virtual void TerminateDataPort() = 0; - virtual void DataPortClosing() = 0; protected: Port portNumbers[NumProtocols]; // port number used for each protocol diff --git a/src/Networking/Socket.h b/src/Networking/Socket.h index aa0aa324..d7525e8e 100644 --- a/src/Networking/Socket.h +++ b/src/Networking/Socket.h @@ -21,14 +21,15 @@ class NetworkInterface; class Socket { public: - Socket(NetworkInterface *iface) : interface(iface), localPort(0), remotePort(0), remoteIPAddress(0) { } + Socket(NetworkInterface *iface) : interface(iface), localPort(0), remotePort(0), remoteIPAddress(0), state(SocketState::disabled) { } NetworkInterface *GetInterface() const { return interface; } - virtual void Poll(bool full) = 0; Port GetLocalPort() const { return localPort; } uint32_t GetRemoteIP() const { return remoteIPAddress; } Port GetRemotePort() const { return remotePort; } NetworkProtocol GetProtocol() const { return protocol; } + + virtual void Poll(bool full) = 0; virtual void Close() = 0; virtual void Terminate() = 0; virtual void TerminateAndDisable() = 0; @@ -52,9 +53,9 @@ protected: aborted }; - NetworkInterface *interface; + NetworkInterface * const interface; Port localPort, remotePort; // The local and remote ports - NetworkProtocol protocol; // What protocol this socket is for + NetworkProtocol protocol; // What protocol this socket is for uint32_t remoteIPAddress; // The remote IP address SocketState state; }; diff --git a/src/Networking/W5500Ethernet/W5500Interface.cpp b/src/Networking/W5500Ethernet/W5500Interface.cpp index 27cf6185..7cb191b0 100644 --- a/src/Networking/W5500Ethernet/W5500Interface.cpp +++ b/src/Networking/W5500Ethernet/W5500Interface.cpp @@ -277,7 +277,7 @@ void W5500Interface::Spin(bool full) { // IP address is all zeros, so use DHCP // debugPrintf("Link established, getting IP address\n"); - DHCP_init(DhcpSocketNumber, reprap.GetNetwork().GetHostname()); + DHCP_init(DhcpSocketNumber, platform.Random(), reprap.GetNetwork().GetHostname()); lastTickMillis = millis(); state = NetworkState::obtainingIP; } @@ -344,7 +344,7 @@ void W5500Interface::Spin(bool full) DHCP_time_handler(); } const DhcpRunResult ret = DHCP_run(); - if (ret == DhcpRunResult::DHCP_IP_CHANGED) + if (ret == DhcpRunResult::DHCP_IP_CHANGED || ret == DhcpRunResult::DHCP_IP_ASSIGN) { // debugPrintf("IP address changed\n"); getSIPR(ipAddress); @@ -440,13 +440,6 @@ void W5500Interface::InitSockets() nextSocketToPoll = 0; } -// The following is called by the FTP responder to stop listening on the FTP data port -// For the W5500 listening stop automatically when the port is terminated, so we don't need anything here -void W5500Interface::DataPortClosing() -{ - // nothing needed here -} - void W5500Interface::TerminateSockets() { for (SocketNumber skt = 0; skt < NumW5500TcpSockets; ++skt) diff --git a/src/Networking/W5500Ethernet/W5500Interface.h b/src/Networking/W5500Ethernet/W5500Interface.h index 69fa1433..3f20b7ab 100644 --- a/src/Networking/W5500Ethernet/W5500Interface.h +++ b/src/Networking/W5500Ethernet/W5500Interface.h @@ -40,8 +40,6 @@ public: void Exit() override; void Spin(bool full) override; void Diagnostics(MessageType mtype) override; - void Start() override; - void Stop() override; GCodeResult EnableInterface(int mode, const StringRef& ssid, const StringRef& reply) override; // enable or disable the network GCodeResult EnableProtocol(NetworkProtocol protocol, int port, int secure, const StringRef& reply) override; @@ -60,7 +58,6 @@ public: void OpenDataPort(Port port) override; void TerminateDataPort() override; - void DataPortClosing() override; private: enum class NetworkState @@ -73,6 +70,8 @@ private: active // network running }; + void Start(); + void Stop(); void InitSockets(); void TerminateSockets(); diff --git a/src/Networking/W5500Ethernet/W5500Socket.cpp b/src/Networking/W5500Ethernet/W5500Socket.cpp index 03340d58..8e200352 100644 --- a/src/Networking/W5500Ethernet/W5500Socket.cpp +++ b/src/Networking/W5500Ethernet/W5500Socket.cpp @@ -17,7 +17,7 @@ const unsigned int MaxBuffersPerSocket = 4; W5500Socket::W5500Socket(NetworkInterface *iface) - : Socket(iface), receivedData(nullptr), state(SocketState::disabled) + : Socket(iface), receivedData(nullptr) { } @@ -171,12 +171,13 @@ void W5500Socket::Poll(bool full) state = SocketState::connected; sendOutstanding = false; } - else + else if (millis() - whenConnected >= FindResponderTimeout) { - if (millis() - whenConnected >= FindResponderTimeout) + if (reprap.Debug(moduleNetwork)) { - Terminate(); + debugPrintf("Timed out waiting for resonder for port %u\n", localPort); } + Terminate(); } } @@ -213,14 +214,16 @@ void W5500Socket::ReceiveData() { // debugPrintf("%u available\n", len); NetworkBuffer * const lastBuffer = NetworkBuffer::FindLast(receivedData); - if (lastBuffer != nullptr && (lastBuffer->SpaceLeft() >= len || (lastBuffer->SpaceLeft() != 0 && NetworkBuffer::Count(receivedData) >= MaxBuffersPerSocket))) + // NOTE: reading only part of the received data doesn't work because the wizchip doesn't track the buffer pointer properly. + // We could probably make it work by tracking the buffer pointer ourselves, just as we do when sending data, and using wiz_recv_data_at. + if (lastBuffer != nullptr && lastBuffer->SpaceLeft() >= len) { - const size_t lengthToRead = min<size_t>((size_t)len, lastBuffer->SpaceLeft()); - wiz_recv_data(socketNum, lastBuffer->UnwrittenData(), (uint16_t)lengthToRead); - lastBuffer->dataLength += lengthToRead; + wiz_recv_data(socketNum, lastBuffer->UnwrittenData(), len); + ExecCommand(socketNum, Sn_CR_RECV); + lastBuffer->dataLength += len; if (reprap.Debug(moduleNetwork)) { - debugPrintf("Received %u bytes\n", (unsigned int)lengthToRead); + debugPrintf("Appended %u bytes\n", (unsigned int)len); } } else if (NetworkBuffer::Count(receivedData) < MaxBuffersPerSocket) diff --git a/src/Networking/W5500Ethernet/W5500Socket.h b/src/Networking/W5500Ethernet/W5500Socket.h index d9799e4f..bc00827f 100644 --- a/src/Networking/W5500Ethernet/W5500Socket.h +++ b/src/Networking/W5500Ethernet/W5500Socket.h @@ -18,47 +18,29 @@ class W5500Socket : public Socket public: W5500Socket(NetworkInterface *iface); void Init(SocketNumber s, Port serverPort, NetworkProtocol p); - void TerminateAndDisable(); - void Poll(bool full); - Port GetLocalPort() const { return localPort; } - uint32_t GetRemoteIP() const { return remoteIPAddress; } - Port GetRemotePort() const { return remotePort; } - void Close(); - void Terminate(); - bool ReadChar(char& c); - bool ReadBuffer(const uint8_t *&buffer, size_t &len); - void Taken(size_t len); - bool CanRead() const; - bool CanSend() const; - size_t Send(const uint8_t *data, size_t length); - void Send(); -private: - enum class SocketState : uint8_t - { - disabled, - inactive, - listening, - connected, - clientDisconnecting, - closing, - aborted - }; + void Poll(bool full) override; + void Close() override; + void Terminate() override; + void TerminateAndDisable() override; + bool ReadChar(char& c) override; + bool ReadBuffer(const uint8_t *&buffer, size_t &len) override; + void Taken(size_t len) override; + bool CanRead() const override; + bool CanSend() const override; + size_t Send(const uint8_t *data, size_t length) override; + void Send() override; +private: void ReInit(); void ReceiveData(); void DiscardReceivedData(); - Port localPort, remotePort; // The local and remote ports - NetworkProtocol protocol; // What protocol this socket is for - uint32_t remoteIPAddress; // The remote IP address NetworkBuffer *receivedData; // List of buffers holding received data - //invariant(!receivedData->IsEmpty()) uint32_t whenConnected; bool persistConnection; // Do we expect this connection to stay alive? bool isTerminated; // Will be true if the connection has gone down unexpectedly (TCP RST) SocketNumber socketNum; // The W5500 socket number we are using - SocketState state; bool sendOutstanding; // True if we have written data to the socket but not flushed it bool isSending; // True if we have written data to the W5500 to send and have not yet seen success or timeout uint16_t wizTxBufferPtr; // Current offset into the Wizchip send buffer, if sendOutstanding is true diff --git a/src/Networking/W5500Ethernet/Wiznet/Ethernet/W5500/w5500.cpp b/src/Networking/W5500Ethernet/Wiznet/Ethernet/W5500/w5500.cpp index b077e76e..364133f5 100644 --- a/src/Networking/W5500Ethernet/Wiznet/Ethernet/W5500/w5500.cpp +++ b/src/Networking/W5500Ethernet/Wiznet/Ethernet/W5500/w5500.cpp @@ -161,11 +161,20 @@ void wiz_recv_data(uint8_t sn, uint8_t *wizdata, uint16_t len) const uint32_t addrsel = ((uint32_t)ptr << 8) + (WIZCHIP_RXBUF_BLOCK(sn) << 3); WIZCHIP_READ_BUF(addrsel, wizdata, len); ptr += len; - - setSn_RX_RD(sn,ptr); + setSn_RX_RD(sn, ptr); } } +// Function wiz_recv_data only works if we read the entire received data. +// This function should get round that, but the caller will have to track the received buffer pointer. +void wiz_recv_data_at(uint8_t sn, uint8_t *wizdata, uint16_t len, uint16_t ptr) +{ + if (len != 0) + { + const uint32_t addrsel = ((uint32_t)ptr << 8) + (WIZCHIP_RXBUF_BLOCK(sn) << 3); + WIZCHIP_READ_BUF(addrsel, wizdata, len); + } +} void wiz_recv_ignore(uint8_t sn, uint16_t len) { diff --git a/src/Networking/W5500Ethernet/Wiznet/Ethernet/W5500/w5500.h b/src/Networking/W5500Ethernet/Wiznet/Ethernet/W5500/w5500.h index 022419a3..e14c71ab 100644 --- a/src/Networking/W5500Ethernet/Wiznet/Ethernet/W5500/w5500.h +++ b/src/Networking/W5500Ethernet/Wiznet/Ethernet/W5500/w5500.h @@ -2287,6 +2287,9 @@ void wiz_send_data_at(uint8_t sn, const uint8_t *wizdata, uint16_t len, uint16_t */ void wiz_recv_data(uint8_t sn, uint8_t *wizdata, uint16_t len); +// Alternative to wiz_recv_data to work around an apparent bug +void wiz_recv_data_at(uint8_t sn, uint8_t *wizdata, uint16_t len, uint16_t ptr); + /** * @ingroup Basic_IO_function * @brief It discard the received data in RX memory. diff --git a/src/Networking/W5500Ethernet/Wiznet/Ethernet/socketlib.cpp b/src/Networking/W5500Ethernet/Wiznet/Ethernet/socketlib.cpp index bfaa9694..01320fa8 100644 --- a/src/Networking/W5500Ethernet/Wiznet/Ethernet/socketlib.cpp +++ b/src/Networking/W5500Ethernet/Wiznet/Ethernet/socketlib.cpp @@ -90,6 +90,11 @@ uint8_t sock_pack_info[_WIZCHIP_SOCK_NUM_] = {0,}; if(len == 0) return SOCKERR_DATALEN; \ }while(0); \ +bool IsSending(uint8_t sn) +{ + return (sock_is_sending & (1u << sn)) != 0; +} + void ExecCommand(uint8_t sn, uint8_t cmd) { setSn_CR(sn, cmd); @@ -248,146 +253,11 @@ int8_t connect(uint8_t sn, uint8_t * addr, uint16_t port) return SOCK_OK; } -int8_t disconnect(uint8_t sn) -{ - CHECK_SOCKMODE(Sn_MR_TCP); - ExecCommand(sn, Sn_CR_DISCON); - - sock_is_sending &= ~(1<<sn); - if (sock_io_mode & (1<<sn)) - { - return SOCK_BUSY; - } - while(getSn_SR(sn) != SOCK_CLOSED) - { - if (getSn_IR(sn) & Sn_IR_TIMEOUT) - { - close(sn); - return SOCKERR_TIMEOUT; - } - } - return SOCK_OK; -} - void disconnectNoWait(uint8_t sn) { ExecCommand(sn, Sn_CR_DISCON); } -int32_t send(uint8_t sn, uint8_t * buf, uint16_t len) -{ - CHECK_SOCKMODE(Sn_MR_TCP); - CHECK_SOCKDATA(); - uint8_t tmp = getSn_SR(sn); - if (tmp != SOCK_ESTABLISHED && tmp != SOCK_CLOSE_WAIT) - { - return SOCKERR_SOCKSTATUS; - } - if ( sock_is_sending & (1<<sn) ) - { - tmp = getSn_IR(sn); - if (tmp & Sn_IR_SENDOK) - { - setSn_IR(sn, Sn_IR_SENDOK); - sock_is_sending &= ~(1<<sn); - } - else if(tmp & Sn_IR_TIMEOUT) - { - close(sn); - return SOCKERR_TIMEOUT; - } - else - { - return SOCK_BUSY; - } - } - uint16_t freesize = getSn_TxMAX(sn); - if (len > freesize) - { - len = freesize; // check size not to exceed MAX size. - } - while(1) - { - freesize = getSn_TX_FSR(sn); - tmp = getSn_SR(sn); - if ((tmp != SOCK_ESTABLISHED) && (tmp != SOCK_CLOSE_WAIT)) - { - close(sn); - return SOCKERR_SOCKSTATUS; - } - if ( (sock_io_mode & (1<<sn)) && (len > freesize) ) - { - return SOCK_BUSY; - } - if (len <= freesize) - { - break; - } - DEBUG_PRINTF("Socket %u need %u free %u\n", sn, len, freesize); - } - wiz_send_data(sn, buf, len); - - ExecCommand(sn, Sn_CR_SEND); - sock_is_sending |= (1 << sn); - return (int32_t)len; -} - - -int32_t recv(uint8_t sn, uint8_t * buf, uint16_t len) -{ - CHECK_SOCKMODE(Sn_MR_TCP); - CHECK_SOCKDATA(); - - uint16_t recvsize = getSn_RxMAX(sn); - if (recvsize < len) - { - len = recvsize; - } - - while(1) - { - recvsize = getSn_RX_RSR(sn); - const uint8_t tmp = getSn_SR(sn); - if (tmp != SOCK_ESTABLISHED) - { - if (tmp == SOCK_CLOSE_WAIT) - { - if (recvsize != 0) - { - break; - } - else if(getSn_TX_FSR(sn) == getSn_TxMAX(sn)) - { - close(sn); - return SOCKERR_SOCKSTATUS; - } - } - else - { - close(sn); - return SOCKERR_SOCKSTATUS; - } - } - if ((sock_io_mode & (1<<sn)) && (recvsize == 0)) - { - return SOCK_BUSY; - } - if (recvsize != 0) - { - break; - } - }; - - if (recvsize < len) - { - len = recvsize; - } - wiz_recv_data(sn, buf, len); - ExecCommand(sn, Sn_CR_RECV); - - return (int32_t)len; -} - int32_t sendto(uint8_t sn, const uint8_t * buf, uint16_t len, const uint8_t * addr, uint16_t port) { switch(getSn_MR(sn) & 0x0F) @@ -426,49 +296,41 @@ int32_t sendto(uint8_t sn, const uint8_t * buf, uint16_t len, const uint8_t * ad len = freesize; // check size not to exceed MAX size. } - while(1) + freesize = getSn_TX_FSR(sn); + if (getSn_SR(sn) == SOCK_CLOSED) { - freesize = getSn_TX_FSR(sn); - if (getSn_SR(sn) == SOCK_CLOSED) - { - return SOCKERR_SOCKCLOSED; - } - if ( (sock_io_mode & (1<<sn)) && (len > freesize) ) - { - return SOCK_BUSY; - } - if (len <= freesize) - { - break; - } - DEBUG_PRINTF("Socket %u need %u free %u\n", sn, len, freesize); - }; + return SOCKERR_SOCKCLOSED; + } + if (len > freesize) + { + return SOCK_BUSY; + } wiz_send_data(sn, buf, len); ExecCommand(sn, Sn_CR_SEND); + sock_is_sending |= 1u << sn; + return (int32_t)len; +} - while(1) +int32_t CheckSendComplete(uint8_t sn) +{ + const uint8_t tmp = getSn_IR(sn); + if (tmp & Sn_IR_SENDOK) { - const uint8_t tmp = getSn_IR(sn); - if (tmp & Sn_IR_SENDOK) - { - setSn_IR(sn, Sn_IR_SENDOK); - break; - } - else if(tmp & Sn_IR_TIMEOUT) - { - setSn_IR(sn, Sn_IR_TIMEOUT); - return SOCKERR_TIMEOUT; - } - DEBUG_PRINTF("Socket %u waiting for send to complete, IR=%02x\n", sn, tmp); -#ifdef _SOCKET_DEBUG_ - delay(10); // to avoid too many messages -#endif + setSn_IR(sn, Sn_IR_SENDOK); + sock_is_sending &= ~(1u << sn); + return SOCK_OK; } - return (int32_t)len; + else if(tmp & Sn_IR_TIMEOUT) + { + setSn_IR(sn, Sn_IR_TIMEOUT); + sock_is_sending &= ~(1u << sn); + return SOCKERR_TIMEOUT; + } + DEBUG_PRINTF("Socket %u waiting for send to complete, IR=%02x\n", sn, tmp); + return SOCK_BUSY; } - int32_t recvfrom(uint8_t sn, uint8_t * buf, uint16_t len, uint8_t * addr, uint16_t *port) { const uint8_t mr = getSn_MR(sn); diff --git a/src/Networking/W5500Ethernet/Wiznet/Ethernet/socketlib.h b/src/Networking/W5500Ethernet/Wiznet/Ethernet/socketlib.h index f85c645e..167711de 100644 --- a/src/Networking/W5500Ethernet/Wiznet/Ethernet/socketlib.h +++ b/src/Networking/W5500Ethernet/Wiznet/Ethernet/socketlib.h @@ -209,75 +209,15 @@ int8_t listen(uint8_t sn); */ int8_t connect(uint8_t sn, uint8_t * addr, uint16_t port); -/** - * @ingroup WIZnet_socket_APIs - * @brief Try to disconnect a connection socket. - * @details It sends request message to disconnect the TCP socket 'sn' passed as parameter to the server or client. - * @note It is valid only in TCP server or client mode. \n - * In block io mode, it does not return until disconnection is completed. \n - * In Non-block io mode, it return @ref SOCK_BUSY immediately. \n - - * @param sn Socket number. It should be <b>0 ~ @ref \_WIZCHIP_SOCK_NUM_</b>. - * @return @b Success : @ref SOCK_OK \n - * @b Fail :\n @ref SOCKERR_SOCKNUM - Invalid socket number \n - * @ref SOCKERR_SOCKMODE - Invalid operation in the socket \n - * @ref SOCKERR_TIMEOUT - Timeout occurred \n - * @ref SOCK_BUSY - Socket is busy. - */ -int8_t disconnect(uint8_t sn); - void disconnectNoWait(uint8_t sn); /** * @ingroup WIZnet_socket_APIs - * @brief Send data to the connected peer in TCP socket. - * @details It is used to send outgoing data to the connected socket. - * @note It is valid only in TCP server or client mode. It can't send data greater than socket buffer size. \n - * In block io mode, It doesn't return until data send is completed - socket buffer size is greater than data. \n - * In non-block io mode, It return @ref SOCK_BUSY immediately when socket buffer is not enough. \n - * @param sn Socket number. It should be <b>0 ~ @ref \_WIZCHIP_SOCK_NUM_</b>. - * @param buf Pointer buffer containing data to be sent. - * @param len The byte length of data in buf. - * @return @b Success : The sent data size \n - * @b Fail : \n @ref SOCKERR_SOCKSTATUS - Invalid socket status for socket operation \n - * @ref SOCKERR_TIMEOUT - Timeout occurred \n - * @ref SOCKERR_SOCKMODE - Invalid operation in the socket \n - * @ref SOCKERR_SOCKNUM - Invalid socket number \n - * @ref SOCKERR_DATALEN - zero data length \n - * @ref SOCK_BUSY - Socket is busy. - */ -int32_t send(uint8_t sn, uint8_t * buf, uint16_t len); - -/** - * @ingroup WIZnet_socket_APIs - * @brief Receive data from the connected peer. - * @details It is used to read incoming data from the connected socket.\n - * It waits for data as much as the application wants to receive. - * @note It is valid only in TCP server or client mode. It can't receive data greater than socket buffer size. \n - * In block io mode, it doesn't return until data reception is completed - data is filled as <I>len</I> in socket buffer. \n - * In non-block io mode, it return @ref SOCK_BUSY immediately when <I>len</I> is greater than data size in socket buffer. \n - * - * @param sn Socket number. It should be <b>0 ~ @ref \_WIZCHIP_SOCK_NUM_</b>. - * @param buf Pointer buffer to read incoming data. - * @param len The max data length of data in buf. - * @return @b Success : The real received data size \n - * @b Fail :\n - * @ref SOCKERR_SOCKSTATUS - Invalid socket status for socket operation \n - * @ref SOCKERR_SOCKMODE - Invalid operation in the socket \n - * @ref SOCKERR_SOCKNUM - Invalid socket number \n - * @ref SOCKERR_DATALEN - zero data length \n - * @ref SOCK_BUSY - Socket is busy. - */ -int32_t recv(uint8_t sn, uint8_t * buf, uint16_t len); - -/** - * @ingroup WIZnet_socket_APIs * @brief Sends datagram to the peer with destination IP address and port number passed as parameter. * @details It sends datagram of UDP or MACRAW to the peer with destination IP address and port number passed as parameter.\n * Even if the connectionless socket has been previously connected to a specific address, * the address and port number parameters override the destination address for that particular datagram only. - * @note In block io mode, It doesn't return until data send is completed - socket buffer size is greater than <I>len</I>. - * In non-block io mode, It return @ref SOCK_BUSY immediately when socket buffer is not enough. + * @note In non-block io mode, It return @ref SOCK_BUSY immediately when socket buffer is not enough. * * @param sn Socket number. It should be <b>0 ~ @ref \_WIZCHIP_SOCK_NUM_</b>. * @param buf Pointer buffer to send outgoing data. @@ -285,7 +225,7 @@ int32_t recv(uint8_t sn, uint8_t * buf, uint16_t len); * @param addr Pointer variable of destination IP address. It should be allocated 4 bytes. * @param port Destination port number. * - * @return @b Success : The sent data size \n + * @return @b Success : The queued sent data size \n * @b Fail :\n @ref SOCKERR_SOCKNUM - Invalid socket number \n * @ref SOCKERR_SOCKMODE - Invalid operation in the socket \n * @ref SOCKERR_SOCKSTATUS - Invalid socket status for socket operation \n @@ -419,67 +359,11 @@ typedef enum */ int8_t ctlsocket(uint8_t sn, ctlsock_type cstype, void* arg); -/** - * @ingroup WIZnet_socket_APIs - * @brief set socket options - * @details Set socket option like as TTL, MSS, TOS, and so on. Refer to @ref sockopt_type. - * - * @param sn socket number - * @param sotype socket option type. refer to @ref sockopt_type - * @param arg Data type and value is determined according to <I>sotype</I>. \n - * <table> - * <tr> <td> @b sotype </td> <td> @b data type</td><td>@b value</td></tr> - * <tr> <td> @ref SO_TTL </td> <td> uint8_t </td><td> 0 ~ 255 </td> </tr> - * <tr> <td> @ref SO_TOS </td> <td> uint8_t </td><td> 0 ~ 255 </td> </tr> - * <tr> <td> @ref SO_MSS </td> <td> uint16_t </td><td> 0 ~ 65535 </td> </tr> - * <tr> <td> @ref SO_DESTIP </td> <td> uint8_t[4] </td><td> </td></tr> - * <tr> <td> @ref SO_DESTPORT </td> <td> uint16_t </td><td> 0 ~ 65535 </td></tr> - * <tr> <td> @ref SO_KEEPALIVESEND </td> <td> null </td><td> null </td></tr> - * <tr> <td> @ref SO_KEEPALIVEAUTO </td> <td> uint8_t </td><td> 0 ~ 255 </td></tr> - * </table> - * @return - * - @b Success : @ref SOCK_OK \n - * - @b Fail - * - @ref SOCKERR_SOCKNUM - Invalid Socket number \n - * - @ref SOCKERR_SOCKMODE - Invalid socket mode \n - * - @ref SOCKERR_SOCKOPT - Invalid socket option or its value \n - * - @ref SOCKERR_TIMEOUT - Timeout occurred when sending keep-alive packet \n - */ -int8_t setsockopt(uint8_t sn, sockopt_type sotype, void* arg); +// Check whether we are sending on a socket +bool IsSending(uint8_t sn); -/** - * @ingroup WIZnet_socket_APIs - * @brief get socket options - * @details Get socket option like as FLAG, TTL, MSS, and so on. Refer to @ref sockopt_type - * @param sn socket number - * @param sotype socket option type. refer to @ref sockopt_type - * @param arg Data type and value is determined according to <I>sotype</I>. \n - * <table> - * <tr> <td> @b sotype </td> <td>@b data type</td><td>@b value</td></tr> - * <tr> <td> @ref SO_FLAG </td> <td> uint8_t </td><td> @ref SF_ETHER_OWN, etc... </td> </tr> - * <tr> <td> @ref SO_TOS </td> <td> uint8_t </td><td> 0 ~ 255 </td> </tr> - * <tr> <td> @ref SO_MSS </td> <td> uint16_t </td><td> 0 ~ 65535 </td> </tr> - * <tr> <td> @ref SO_DESTIP </td> <td> uint8_t[4] </td><td> </td></tr> - * <tr> <td> @ref SO_DESTPORT </td> <td> uint16_t </td><td> </td></tr> - * <tr> <td> @ref SO_KEEPALIVEAUTO </td> <td> uint8_t </td><td> 0 ~ 255 </td></tr> - * <tr> <td> @ref SO_SENDBUF </td> <td> uint16_t </td><td> 0 ~ 65535 </td></tr> - * <tr> <td> @ref SO_RECVBUF </td> <td> uint16_t </td><td> 0 ~ 65535 </td></tr> - * <tr> <td> @ref SO_STATUS </td> <td> uint8_t </td><td> @ref SOCK_ESTABLISHED, etc.. </td></tr> - * <tr> <td> @ref SO_REMAINSIZE </td> <td> uint16_t </td><td> 0~ 65535 </td></tr> - * <tr> <td> @ref SO_PACKINFO </td> <td> uint8_t </td><td> @ref PACK_FIRST, etc... </td></tr> - * </table> - * @return - * - @b Success : @ref SOCK_OK \n - * - @b Fail - * - @ref SOCKERR_SOCKNUM - Invalid Socket number \n - * - @ref SOCKERR_SOCKOPT - Invalid socket option or its value \n - * - @ref SOCKERR_SOCKMODE - Invalid socket mode \n - * @note - * The option as PACK_REMAINED and SO_PACKINFO is valid only in NON-TCP mode and after call @ref recvfrom(). \n - * When SO_PACKINFO value is PACK_FIRST and the return value of recvfrom() is zero, - * This means the zero byte UDP data(UDP Header only) received. - */ -int8_t getsockopt(uint8_t sn, sockopt_type sotype, void* arg); +// Check whether sending on a socket is complete +int32_t CheckSendComplete(uint8_t sn); // pre(IsSending()) // Execute a command void ExecCommand(uint8_t sn, uint8_t cmd); diff --git a/src/Networking/W5500Ethernet/Wiznet/Internet/DHCP/dhcp.cpp b/src/Networking/W5500Ethernet/Wiznet/Internet/DHCP/dhcp.cpp index 661ea0f3..5b325645 100644 --- a/src/Networking/W5500Ethernet/Wiznet/Internet/DHCP/dhcp.cpp +++ b/src/Networking/W5500Ethernet/Wiznet/Internet/DHCP/dhcp.cpp @@ -65,13 +65,18 @@ extern "C" void debugPrintf(const char *fmt, ...); #endif /* DHCP state machine. */ -#define STATE_DHCP_INIT 0 ///< Initialize -#define STATE_DHCP_DISCOVER 1 ///< send DISCOVER and wait OFFER -#define STATE_DHCP_REQUEST 2 ///< send REQEUST and wait ACK or NACK -#define STATE_DHCP_LEASED 3 ///< ReceiveD ACK and IP leased -#define STATE_DHCP_REREQUEST 4 ///< send REQUEST for maintaining leased IP -#define STATE_DHCP_RELEASE 5 ///< No use -#define STATE_DHCP_STOP 6 ///< Stop processing DHCP +enum class DhcpState : uint8_t +{ + init = 0, ///< Initialize + discover, ///< send DISCOVER and wait OFFER + request, ///< send REQUEST and wait ACK or NACK + leased, ///< Received ACK and IP leased + rerequest, ///< send REQUEST for maintaining leased IP + release, ///< No use + stop, ///< Stop processing DHCP + checkingIpConflict, ///< Waiting for send to conflicting IP to complete + delaying +}; #define DHCP_FLAGSBROADCAST 0x8000 ///< The broadcast value of flags in @ref RIP_MSG #define DHCP_FLAGSUNICAST 0x0000 ///< The unicast value of flags in @ref RIP_MSG @@ -81,6 +86,7 @@ extern "C" void debugPrintf(const char *fmt, ...); #define DHCP_BOOTREPLY 2 ///< Reply Message used i op of @ref RIP_MSG /* DHCP message type */ +#define DHCP_NOTYPE 0 // must be different from all of the following #define DHCP_DISCOVER 1 ///< DISCOVER message in OPT of @ref RIP_MSG #define DHCP_OFFER 2 ///< OFFER message in OPT of @ref RIP_MSG #define DHCP_REQUEST 3 ///< REQUEST message in OPT of @ref RIP_MSG @@ -207,14 +213,16 @@ uint8_t DHCP_allocated_sn[4] = {0, }; // Subnet mask from DHCP uint8_t DHCP_allocated_dns[4] = {0, }; // DNS address from DHCP -int8_t dhcp_state = STATE_DHCP_INIT; // DHCP state -int8_t dhcp_retry_count = 0; +DhcpState dhcp_state = DhcpState::init; // DHCP state +int8_t dhcp_retry_count; + +uint32_t dhcp_lease_time; +volatile uint32_t dhcp_tick_1s; // unit 1 second +uint32_t dhcp_tick_next; -uint32_t dhcp_lease_time = INFINITE_LEASETIME; -volatile uint32_t dhcp_tick_1s = 0; // unit 1 second -uint32_t dhcp_tick_next = DHCP_WAIT_TIME ; +uint32_t DHCP_XID; // Any number -uint32_t DHCP_XID; // Any number +int32_t dhcpLastSendStatus; static RIP_MSG dhcpMessageBuffer; RIP_MSG* const pDHCPMSG = &dhcpMessageBuffer; // Buffer pointer for DHCP processing @@ -245,7 +253,7 @@ void send_DHCP_REQUEST(void); void send_DHCP_DECLINE(void); /* IP conflict check by sending ARP-request to leased IP and wait ARP-response. */ -bool check_DHCP_leasedIP(void); +void check_DHCP_leasedIP(void); /* check the timeout in DHCP process */ DhcpRunResult check_DHCP_timeout(void); @@ -416,7 +424,7 @@ void send_DHCP_DISCOVER(void) DEBUG_PRINTF("> Send DHCP_DISCOVER\n"); - sendto(DHCP_SOCKET, (uint8_t *)pDHCPMSG, RIP_MSG_SIZE, ip, DHCP_SERVER_PORT); + (void)sendto(DHCP_SOCKET, (uint8_t *)pDHCPMSG, RIP_MSG_SIZE, ip, DHCP_SERVER_PORT); DEBUG_PRINTF("Sent\n"); } @@ -427,7 +435,7 @@ void send_DHCP_REQUEST(void) makeDHCPMSG(); uint8_t ip[4]; - if (dhcp_state == STATE_DHCP_LEASED || dhcp_state == STATE_DHCP_REREQUEST) + if (dhcp_state == DhcpState::leased || dhcp_state == DhcpState::rerequest) { *((uint8_t*)(&pDHCPMSG->flags)) = ((DHCP_FLAGSUNICAST & 0xFF00)>> 8); *((uint8_t*)(&pDHCPMSG->flags)+1) = (DHCP_FLAGSUNICAST & 0x00FF); @@ -465,7 +473,7 @@ void send_DHCP_REQUEST(void) pDHCPMSG->OPT[k++] = DHCP_CHADDR[4]; pDHCPMSG->OPT[k++] = DHCP_CHADDR[5]; - if (ip[3] == 255) // if(dchp_state == STATE_DHCP_LEASED || dchp_state == DHCP_REREQUEST_STATE) + if (dhcp_state != DhcpState::leased && dhcp_state != DhcpState::rerequest) { pDHCPMSG->OPT[k++] = dhcpRequestedIPaddr; pDHCPMSG->OPT[k++] = 0x04; @@ -510,7 +518,7 @@ void send_DHCP_REQUEST(void) DEBUG_PRINTF("> Send DHCP_REQUEST\n"); - sendto(DHCP_SOCKET, (uint8_t *)pDHCPMSG, RIP_MSG_SIZE, ip, DHCP_SERVER_PORT); + (void)sendto(DHCP_SOCKET, (uint8_t *)pDHCPMSG, RIP_MSG_SIZE, ip, DHCP_SERVER_PORT); } /* SEND DHCP DHCPDECLINE */ @@ -568,13 +576,13 @@ void send_DHCP_DECLINE(void) DEBUG_PRINTF("\n> Send DHCP_DECLINE\n"); - sendto(DHCP_SOCKET, (uint8_t *)pDHCPMSG, RIP_MSG_SIZE, ip, DHCP_SERVER_PORT); + (void)sendto(DHCP_SOCKET, (uint8_t *)pDHCPMSG, RIP_MSG_SIZE, ip, DHCP_SERVER_PORT); } /* PARSE REPLY pDHCPMSG */ int8_t parseDHCPMSG(void) { - uint8_t type = 0; + uint8_t type = DHCP_NOTYPE; uint16_t len; if ((len = getSn_RX_RSR(DHCP_SOCKET)) > 0) { @@ -587,9 +595,9 @@ int8_t parseDHCPMSG(void) uint16_t svr_port; len = recvfrom(DHCP_SOCKET, (uint8_t *)pDHCPMSG, len, svr_addr, &svr_port); - DEBUG_PRINTF("DHCP message : %d.%d.%d.%d(%d) %d received. \n", svr_addr[0], svr_addr[1], svr_addr[2], svr_addr[3],svr_port, len); + DEBUG_PRINTF("DHCP message : %d.%d.%d.%d(%d) %d received. \n", svr_addr[0], svr_addr[1], svr_addr[2], svr_addr[3], svr_port, len); - if (svr_port == DHCP_SERVER_PORT) + if (svr_port == DHCP_SERVER_PORT && len > 240) { // compare mac address if ( (pDHCPMSG->chaddr[0] == DHCP_CHADDR[0]) && (pDHCPMSG->chaddr[1] == DHCP_CHADDR[1]) @@ -687,7 +695,7 @@ int8_t parseDHCPMSG(void) DhcpRunResult DHCP_run(void) { - if (dhcp_state == STATE_DHCP_STOP) + if (dhcp_state == DhcpState::stop) { return DhcpRunResult::DHCP_STOPPED; } @@ -698,20 +706,29 @@ DhcpRunResult DHCP_run(void) } DhcpRunResult ret = DhcpRunResult::DHCP_RUNNING; + if (IsSending(DHCP_SOCKET)) + { + dhcpLastSendStatus = CheckSendComplete(DHCP_SOCKET); + if (dhcpLastSendStatus == SOCK_BUSY) + { + return ret; + } + } + const uint8_t type = parseDHCPMSG(); switch (dhcp_state) { - case STATE_DHCP_INIT: + case DhcpState::init: DHCP_allocated_ip[0] = 0; DHCP_allocated_ip[1] = 0; DHCP_allocated_ip[2] = 0; DHCP_allocated_ip[3] = 0; send_DHCP_DISCOVER(); - dhcp_state = STATE_DHCP_DISCOVER; + dhcp_state = DhcpState::discover; break; - case STATE_DHCP_DISCOVER: + case DhcpState::discover: if (type == DHCP_OFFER) { DEBUG_PRINTF("> Receive DHCP_OFFER\n"); @@ -721,7 +738,7 @@ DhcpRunResult DHCP_run(void) DHCP_allocated_ip[3] = pDHCPMSG->yiaddr[3]; send_DHCP_REQUEST(); - dhcp_state = STATE_DHCP_REQUEST; + dhcp_state = DhcpState::request; } else { @@ -729,31 +746,32 @@ DhcpRunResult DHCP_run(void) } break; - case STATE_DHCP_REQUEST : + case DhcpState::request: if (type == DHCP_ACK) { - DEBUG_PRINTF("> Receive DHCP_ACK\n"); - if (check_DHCP_leasedIP()) + DEBUG_PRINTF("> Receive DHCP_ACK, lease time = %u\n", (unsigned int)dhcp_lease_time); + uint8_t currentIp[4]; + getSIPR(currentIp); + if (memcmp(DHCP_allocated_ip, currentIp, 4) == 0) { - // Network info assignment from DHCP - dhcp_ip_assign(); + // We have been given the IP address we are already using. + // Don't check for an address conflict, because I have a suspicion that we end up replying to the ARP request ourselves. + dhcp_ip_assign(); // in case gateway or subnet mask have changed reset_DHCP_timeout(); - dhcp_state = STATE_DHCP_LEASED; + dhcp_state = DhcpState::leased; ret = DhcpRunResult::DHCP_IP_ASSIGN; } else { - // IP address conflict occurred - reset_DHCP_timeout(); - dhcp_ip_conflict(); - dhcp_state = STATE_DHCP_INIT; + check_DHCP_leasedIP(); + dhcp_state = DhcpState::checkingIpConflict; } } else if (type == DHCP_NAK) { DEBUG_PRINTF("> Receive DHCP_NACK\n"); reset_DHCP_timeout(); - dhcp_state = STATE_DHCP_DISCOVER; + dhcp_state = DhcpState::discover; } else { @@ -761,11 +779,40 @@ DhcpRunResult DHCP_run(void) } break; - case STATE_DHCP_LEASED : + case DhcpState::checkingIpConflict: + if (dhcpLastSendStatus == SOCKERR_TIMEOUT) + { + // UDP send Timeout occurred, so allocated IP address is unique, DHCP Success + DEBUG_PRINTF("\n> Check leased IP - OK\n"); + dhcp_ip_assign(); + reset_DHCP_timeout(); + dhcp_state = DhcpState::leased; + ret = DhcpRunResult::DHCP_IP_ASSIGN; + } + else + { + // Received ARP reply, so IP address conflict has occurred, DHCP Failed + send_DHCP_DECLINE(); + dhcp_ip_conflict(); + reset_DHCP_timeout(); + dhcp_state = DhcpState::delaying; + } + break; + + case DhcpState::delaying: + // Had IP address conflict. Delay before trying again. + if (dhcp_tick_1s > 3) + { + reset_DHCP_timeout(); + dhcp_state = DhcpState::init; + } + break; + + case DhcpState::leased : ret = DhcpRunResult::DHCP_IP_LEASED; if ((dhcp_lease_time != INFINITE_LEASETIME) && ((dhcp_lease_time/2) < dhcp_tick_1s)) { - DEBUG_PRINTF("> Maintains the IP address \n"); + DEBUG_PRINTF("> Maintain the IP address \n"); OLD_allocated_ip[0] = DHCP_allocated_ip[0]; OLD_allocated_ip[1] = DHCP_allocated_ip[1]; OLD_allocated_ip[2] = DHCP_allocated_ip[2]; @@ -775,11 +822,11 @@ DhcpRunResult DHCP_run(void) send_DHCP_REQUEST(); reset_DHCP_timeout(); - dhcp_state = STATE_DHCP_REREQUEST; + dhcp_state = DhcpState::rerequest; } break; - case STATE_DHCP_REREQUEST : + case DhcpState::rerequest: ret = DhcpRunResult::DHCP_IP_LEASED; if (type == DHCP_ACK) { @@ -798,13 +845,13 @@ DhcpRunResult DHCP_run(void) DEBUG_PRINTF(">IP is continued.\n"); } reset_DHCP_timeout(); - dhcp_state = STATE_DHCP_LEASED; + dhcp_state = DhcpState::leased; } else if (type == DHCP_NAK) { DEBUG_PRINTF("> Receive DHCP_NACK, Failed to maintain ip\n"); reset_DHCP_timeout(); - dhcp_state = STATE_DHCP_DISCOVER; + dhcp_state = DhcpState::discover; } else { @@ -822,7 +869,7 @@ DhcpRunResult DHCP_run(void) void DHCP_stop(void) { close(DHCP_SOCKET); - dhcp_state = STATE_DHCP_STOP; + dhcp_state = DhcpState::stop; } DhcpRunResult check_DHCP_timeout(void) @@ -835,18 +882,18 @@ DhcpRunResult check_DHCP_timeout(void) { switch ( dhcp_state ) { - case STATE_DHCP_DISCOVER : + case DhcpState::discover : DEBUG_PRINTF("<<timeout>> state : STATE_DHCP_DISCOVER\n"); send_DHCP_DISCOVER(); break; - case STATE_DHCP_REQUEST : + case DhcpState::request : DEBUG_PRINTF("<<timeout>> state : STATE_DHCP_REQUEST\n"); send_DHCP_REQUEST(); break; - case STATE_DHCP_REREQUEST : + case DhcpState::rerequest : DEBUG_PRINTF("<<timeout>> state : STATE_DHCP_REREQUEST\n"); send_DHCP_REQUEST(); @@ -865,14 +912,15 @@ DhcpRunResult check_DHCP_timeout(void) { // exceeded retry count switch(dhcp_state) { - case STATE_DHCP_DISCOVER: - dhcp_state = STATE_DHCP_INIT; + case DhcpState::discover: + dhcp_state = DhcpState::init; ret = DhcpRunResult::DHCP_FAILED; break; - case STATE_DHCP_REQUEST: - case STATE_DHCP_REREQUEST: + case DhcpState::request: + case DhcpState::rerequest: + case DhcpState::checkingIpConflict: send_DHCP_DISCOVER(); - dhcp_state = STATE_DHCP_DISCOVER; + dhcp_state = DhcpState::discover; break; default : break; @@ -882,43 +930,22 @@ DhcpRunResult check_DHCP_timeout(void) return ret; } -bool check_DHCP_leasedIP(void) +void check_DHCP_leasedIP(void) { - uint8_t tmp; - int32_t ret; - //WIZchip RCR value changed for ARP Timeout count control - tmp = getRCR(); + const uint8_t tmp = getRCR(); setRCR(0x03); // IP conflict detection : ARP request - ARP reply // Broadcasting ARP Request for check the IP conflict using UDP sendto() function // TODO the following takes 620ms to time out - hanging for this long isn't very nice - ret = sendto(DHCP_SOCKET, (const uint8_t *)"CHECK_IP_CONFLICT", 17, DHCP_allocated_ip, 5000); + sendto(DHCP_SOCKET, (const uint8_t *)"CHECK_IP_CONFLICT", 17, DHCP_allocated_ip, 5000); // RCR value restore setRCR(tmp); - - if (ret == SOCKERR_TIMEOUT) - { - // UDP send Timeout occurred : allocated IP address is unique, DHCP Success - DEBUG_PRINTF("\n> Check leased IP - OK\n"); - return true; - } - else - { - // Received ARP reply or etc : IP address conflict occur, DHCP Failed - send_DHCP_DECLINE(); - - ret = dhcp_tick_1s; - //TODO can't tolerate a 1 to 2 second wait here - while((dhcp_tick_1s - ret) < 2) { } // wait for 1s over; wait to complete to send DECLINE message; - - return false; - } } -void DHCP_init(uint8_t s, const char *hname) +void DHCP_init(uint8_t s, uint32_t seed, const char *hname) { strncpy(HOST_NAME, hname, sizeof(HOST_NAME)); HOST_NAME[sizeof(HOST_NAME) - 1] = 0; @@ -939,8 +966,11 @@ void DHCP_init(uint8_t s, const char *hname) setSHAR(DHCP_CHADDR); } - DHCP_SOCKET = s; // SOCK_DHCP - DHCP_XID = 0x12345678; + DHCP_SOCKET = s; + reset_DHCP_timeout(); + dhcp_lease_time = INFINITE_LEASETIME; + DHCP_XID = seed; + dhcpLastSendStatus = SOCK_OK; // WIZchip Netinfo Clear setSIPR(zeroip); @@ -948,7 +978,7 @@ void DHCP_init(uint8_t s, const char *hname) setGAR(zeroip); reset_DHCP_timeout(); - dhcp_state = STATE_DHCP_INIT; + dhcp_state = DhcpState::init; } /* Rset the DHCP timeout count and retry count. */ diff --git a/src/Networking/W5500Ethernet/Wiznet/Internet/DHCP/dhcp.h b/src/Networking/W5500Ethernet/Wiznet/Internet/DHCP/dhcp.h index 4f238b6e..6148b5eb 100644 --- a/src/Networking/W5500Ethernet/Wiznet/Internet/DHCP/dhcp.h +++ b/src/Networking/W5500Ethernet/Wiznet/Internet/DHCP/dhcp.h @@ -77,7 +77,7 @@ enum class DhcpRunResult : uint8_t * @param s - socket number * @param hname - null-terminated host name string */ -void DHCP_init(uint8_t s, const char *hname); +void DHCP_init(uint8_t s, uint32_t seed, const char *hname); /* * @brief DHCP 1s Tick Timer handler diff --git a/src/Platform.cpp b/src/Platform.cpp index 4e37716e..75f2f517 100644 --- a/src/Platform.cpp +++ b/src/Platform.cpp @@ -357,7 +357,7 @@ void Platform::Init() SERIAL_AUX2_DEVICE.begin(baudRates[2]); #endif - compatibility = marlin; // default to Marlin because the common host programs expect the "OK" response to commands + compatibility = Compatibility::marlin; // default to Marlin because the common host programs expect the "OK" response to commands // File management massStorage->Init(); @@ -366,33 +366,37 @@ void Platform::Init() ARRAY_INIT(netMask, DefaultNetMask); ARRAY_INIT(gateWay, DefaultGateway); -#if defined(DUET_NG) || defined(SAME70_TEST_BOARD) - // On the Duet Ethernet and SAM E70, use the unique chip ID as most of the MAC address. - // The unique ID is 128 bits long whereas the whole MAC address is only 48 bits, - // so we can't guarantee that each Duet will get a unique MAC address this way. +#if SAM4E || SAM4S || SAME70 + // Read the unique ID of the MCU + memset(uniqueId, 0, sizeof(uniqueId)); + DisableCache(); + cpu_irq_disable(); + const uint32_t rc = flash_read_unique_id(uniqueId, 4); + cpu_irq_enable(); + EnableCache(); + + if (rc == 0) { - uint32_t idBuf[4]; - memset(idBuf, 0, sizeof(idBuf)); - DisableCache(); - cpu_irq_disable(); - const uint32_t rc = flash_read_unique_id(idBuf, 4); - cpu_irq_enable(); - EnableCache(); - if (rc == 0) - { - memset(defaultMacAddress, 0, sizeof(defaultMacAddress)); - defaultMacAddress[0] = 0xBE; // use a fixed first byte with the locally-administered bit set - const uint8_t * const idBytes = reinterpret_cast<const uint8_t *>(idBuf); - for (size_t i = 0; i < 15; ++i) - { - defaultMacAddress[(i % 5) + 1] ^= idBytes[i]; - } - } - else + // Put the checksum at the end + // We only print 30 5-bit characters = 128 data bits + 22 checksum bits. So compress the 32 checksum bits into 22. + uniqueId[4] = uniqueId[0] ^ uniqueId[1] ^ uniqueId[2] ^ uniqueId[3]; + uniqueId[4] ^= (uniqueId[4] >> 10); + + // On the Duet Ethernet and SAM E70, use the unique chip ID as most of the MAC address. + // The unique ID is 128 bits long whereas the whole MAC address is only 48 bits, + // so we can't guarantee that each Duet will get a unique MAC address this way. + memset(defaultMacAddress, 0, sizeof(defaultMacAddress)); + defaultMacAddress[0] = 0xBE; // use a fixed first byte with the locally-administered bit set + const uint8_t * const idBytes = reinterpret_cast<const uint8_t *>(uniqueId); + for (size_t i = 0; i < 15; ++i) { - ARRAY_INIT(defaultMacAddress, DefaultMacAddress); + defaultMacAddress[(i % 5) + 1] ^= idBytes[i]; } } + else + { + ARRAY_INIT(defaultMacAddress, DefaultMacAddress); + } #elif defined(DUET_06_085) ARRAY_INIT(defaultMacAddress, DefaultMacAddress); @@ -497,9 +501,6 @@ void Platform::Init() motorCurrents[drive] = 0.0; motorCurrentFraction[drive] = 1.0; -#if HAS_SMART_DRIVERS - motorStandstillCurrentFraction[drive] = 1.0; -#endif driverState[drive] = DriverStatus::disabled; // Enable pullup resistors on endstop inputs here if necessary. @@ -1254,26 +1255,26 @@ void Platform::Exit() Compatibility Platform::Emulating() const { - return (compatibility == reprapFirmware) ? me : compatibility; + return (compatibility == Compatibility::reprapFirmware) ? Compatibility::me : compatibility; } void Platform::SetEmulating(Compatibility c) { - if (c != me && c != reprapFirmware && c != marlin) + if (c != Compatibility::me && c != Compatibility::reprapFirmware && c != Compatibility::marlin) { Message(ErrorMessage, "Attempt to emulate unsupported firmware.\n"); } else { - if (c == reprapFirmware) + if (c == Compatibility::reprapFirmware) { - c = me; + c = Compatibility::me; } compatibility = c; } } -void Platform::UpdateNetworkAddress(byte dst[4], const byte src[4]) +void Platform::UpdateNetworkAddress(uint8_t dst[4], const uint8_t src[4]) { for (uint8_t i = 0; i < 4; i++) { @@ -1282,22 +1283,22 @@ void Platform::UpdateNetworkAddress(byte dst[4], const byte src[4]) reprap.GetNetwork().SetEthernetIPAddress(ipAddress, gateWay, netMask); } -void Platform::SetIPAddress(byte ip[]) +void Platform::SetIPAddress(uint8_t ip[]) { UpdateNetworkAddress(ipAddress, ip); } -void Platform::SetGateWay(byte gw[]) +void Platform::SetGateWay(uint8_t gw[]) { UpdateNetworkAddress(gateWay, gw); } -void Platform::SetNetMask(byte nm[]) +void Platform::SetNetMask(uint8_t nm[]) { UpdateNetworkAddress(netMask, nm); } -// Flush messages to USB and aux, returning true if there is more to send +// Flush messages to aux, returning true if there is more to send bool Platform::FlushAuxMessages() { // Write non-blocking data to the AUX line @@ -1873,7 +1874,7 @@ void Platform::SoftwareReset(uint16_t reason, const uint32_t *stk) } srdBuf[slot].magic = SoftwareResetData::magicValue; srdBuf[slot].resetReason = reason; - srdBuf[slot].when = realTime; + srdBuf[slot].when = (uint32_t)realTime; // some compilers/libraries use 64-bit time_t GetStackUsage(nullptr, nullptr, &srdBuf[slot].neverUsedRam); srdBuf[slot].hfsr = SCB->HFSR; srdBuf[slot].cfsr = SCB->CFSR; @@ -2020,7 +2021,7 @@ void Platform::InitialiseInterrupts() // Interrupt for 4-pin PWM fan sense line if (coolingFanRpmPin != NoPin) { - attachInterrupt(coolingFanRpmPin, FanInterrupt, FALLING, nullptr); + attachInterrupt(coolingFanRpmPin, FanInterrupt, INTERRUPT_MODE_FALLING, nullptr); } // Tick interrupt for ADC conversions @@ -2053,70 +2054,55 @@ void Platform::InitialiseInterrupts() // Print the unique processor ID void Platform::PrintUniqueId(MessageType mtype) { - uint32_t idBuf[5]; - const irqflags_t flags = cpu_irq_save(); - DisableCache(); - const uint32_t rc = flash_read_unique_id(idBuf, 4); - EnableCache(); - cpu_irq_restore(flags); - if (rc == 0) + // Print the unique ID and checksum as 30 base5 alphanumeric digits + char digits[30 + 5 + 1]; // 30 characters, 5 separators, 1 null terminator + char *digitPtr = digits; + for (size_t i = 0; i < 30; ++i) { - // Put the checksum at the end - idBuf[4] = idBuf[0] ^ idBuf[1] ^ idBuf[2] ^ idBuf[3]; - - // We are only going to print 30 5-bit characters = 128 data bits + 22 checksum bits. So compress the 32 checksum bits into 22. - idBuf[4] ^= (idBuf[4] >> 10); - - // Print the unique ID and checksum as 30 base5 alphanumeric digits - char digits[30 + 5 + 1]; // 30 characters, 5 separators, 1 null terminator - char *digitPtr = digits; - for (size_t i = 0; i < 30; ++i) + if ((i % 5) == 0 && i != 0) + { + *digitPtr++ = '-'; + } + const size_t index = (i * 5) / 32; + const size_t shift = (i * 5) % 32; + uint32_t val = uniqueId[index] >> shift; + if (shift > 32 - 5) + { + // We need some bits from the next dword too + val |= uniqueId[index + 1] << (32 - shift); + } + val &= 31; + char c; + if (val < 10) + { + c = val + '0'; + } + else { - if ((i % 5) == 0 && i != 0) + c = val + ('A' - 10); + // We have 26 letters in the usual A-Z alphabet and we only need 22 of them plus 0-9. + // So avoid using letters C, E, I and O which are easily mistaken for G, F, 1 and 0. + if (c >= 'C') { - *digitPtr++ = '-'; + ++c; } - const size_t index = (i * 5) / 32; - const size_t shift = (i * 5) % 32; - uint32_t val = idBuf[index] >> shift; - if (shift > 32 - 5) + if (c >= 'E') { - // We need some bits from the next dword too - val |= idBuf[index + 1] << (32 - shift); + ++c; } - val &= 31; - char c; - if (val < 10) + if (c >= 'I') { - c = val + '0'; + ++c; } - else + if (c >= 'O') { - c = val + ('A' - 10); - // We have 26 letters in the usual A-Z alphabet and we only need 22 of them plus 0-9. - // So avoid using letters C, E, I and O which are easily mistaken for G, F, 1 and 0. - if (c >= 'C') - { - ++c; - } - if (c >= 'E') - { - ++c; - } - if (c >= 'I') - { - ++c; - } - if (c >= 'O') - { - ++c; - } + ++c; } - *digitPtr++ = c; } - *digitPtr = 0; - MessageF(mtype, "Board ID: %s\n", digits); + *digitPtr++ = c; } + *digitPtr = 0; + MessageF(mtype, "Board ID: %s\n", digits); } #endif @@ -2157,7 +2143,7 @@ void Platform::Diagnostics(MessageType mtype) #elif SAM3XA (char *) 0x20070000; #else -# error +# error Unsupported processor #endif const struct mallinfo mi = mallinfo(); MessageF(mtype, "Static ram used: %d\n", &_end - ramstart); @@ -2171,8 +2157,9 @@ void Platform::Diagnostics(MessageType mtype) // Show the up time and reason for the last reset const uint32_t now = (uint32_t)(millis64()/1000u); // get up time in seconds const char* resetReasons[8] = { "power up", "backup", "watchdog", "software", -#if SAM4E || SAM4S - // On the SAM4E a watchdog reset may be reported as a user reset because of the capacitor on the NRST pin +#ifdef DUET_NG + // On the SAM4E a watchdog reset may be reported as a user reset because of the capacitor on the NRST pin. + // The SAM4S is the same but the Duet M has a diode in the reset circuit to avoid this problem. "reset button or watchdog", #else "reset button", @@ -2223,7 +2210,8 @@ void Platform::Diagnostics(MessageType mtype) : "Unknown"; if (srdBuf[slot].when != 0) { - const struct tm * const timeInfo = gmtime(&srdBuf[slot].when); + const time_t when = (time_t)srdBuf[slot].when; + const struct tm * const timeInfo = gmtime(&when); scratchString.printf("at %04u-%02u-%02u %02u:%02u", timeInfo->tm_year + 1900, timeInfo->tm_mon + 1, timeInfo->tm_mday, timeInfo->tm_hour, timeInfo->tm_min); } @@ -2995,7 +2983,7 @@ void Platform::SetDriverCurrent(size_t driver, float currentOrPercent, int code) #if HAS_SMART_DRIVERS case 917: - motorStandstillCurrentFraction[driver] = 0.01 * currentOrPercent; + SmartDrivers::SetStandstillCurrentPercent(driver, currentOrPercent); break; #endif default: @@ -3110,7 +3098,7 @@ float Platform::GetMotorCurrent(size_t drive, int code) const #if HAS_SMART_DRIVERS case 917: - return motorStandstillCurrentFraction[driver] * 100.0; + return (driver < numSmartDrivers) ? SmartDrivers::GetStandstillCurrentPercent(driver) : 100.0; #endif default: break; @@ -3236,18 +3224,18 @@ void Platform::SetEnableValue(size_t driver, int8_t eVal) #endif } -void Platform::SetAxisDriversConfig(size_t drive, const AxisDriversConfig& config) +void Platform::SetAxisDriversConfig(size_t axis, const AxisDriversConfig& config) { - axisDrivers[drive] = config; + axisDrivers[axis] = config; uint32_t bitmap = 0; for (size_t i = 0; i < config.numDrivers; ++i) { bitmap |= CalcDriverBitmap(config.driverNumbers[i]); #if HAS_SMART_DRIVERS - SmartDrivers::SetAxisNumber(config.driverNumbers[i], drive); + SmartDrivers::SetAxisNumber(config.driverNumbers[i], axis); #endif } - driveDriverBits[drive] = bitmap; + driveDriverBits[axis] = bitmap; } // Map an extruder to a driver @@ -3410,14 +3398,14 @@ void Platform::GetEndStopConfiguration(size_t axis, EndStopPosition& esType, End //----------------------------------------------------------------------------------------------------- -void Platform::AppendAuxReply(const char *msg) +void Platform::AppendAuxReply(const char *msg, bool rawMessage) { // Discard this response if either no aux device is attached or if the response is empty if (msg[0] != 0 && HaveAux()) { - if (msg[0] == '{') + if (rawMessage) { - // JSON responses are always sent directly to the AUX device + // Raw responses are sent directly to the AUX device OutputBuffer *buf; if (OutputBuffer::Allocate(buf)) { @@ -3437,14 +3425,14 @@ void Platform::AppendAuxReply(const char *msg) } } -void Platform::AppendAuxReply(OutputBuffer *reply) +void Platform::AppendAuxReply(OutputBuffer *reply, bool rawMessage) { // Discard this response if either no aux device is attached or if the response is empty if (reply == nullptr || reply->Length() == 0 || !HaveAux()) { OutputBuffer::ReleaseAll(reply); } - else if ((*reply)[0] == '{') + else if (rawMessage) { // JSON responses are always sent directly to the AUX device // For big responses it makes sense to write big chunks of data in portions. Store this data here @@ -3481,7 +3469,7 @@ void Platform::RawMessage(MessageType type, const char *message) } else if ((type & LcdMessage) != 0) { - AppendAuxReply(message); + AppendAuxReply(message, (message[0] == '{') || (type & RawMessageFlag) != 0); } if ((type & HttpMessage) != 0) @@ -3597,7 +3585,7 @@ void Platform::Message(const MessageType type, OutputBuffer *buffer) if ((type & (LcdMessage | ImmediateLcdMessage)) != 0) { - AppendAuxReply(buffer); + AppendAuxReply(buffer, ((*buffer)[0] == '{') || (type & RawMessageFlag) != 0); } if ((type & HttpMessage) != 0) @@ -4106,9 +4094,9 @@ bool Platform::GetFirmwarePin(LogicalPin logicalPin, PinAccess access, Pin& firm return false; } -bool Platform::SetExtrusionAncilliaryPwmPin(LogicalPin logicalPin) +bool Platform::SetExtrusionAncilliaryPwmPin(LogicalPin logicalPin, bool invert) { - return extrusionAncilliaryPwmPort.Set(logicalPin, PinAccess::pwm); + return extrusionAncilliaryPwmPort.Set(logicalPin, PinAccess::pwm, invert); } // CNC and laser support @@ -4131,21 +4119,21 @@ void Platform::SetLaserPwm(float pwm) laserPort.WriteAnalog(pwm); } -bool Platform::SetSpindlePins(LogicalPin lpf, LogicalPin lpr) +bool Platform::SetSpindlePins(LogicalPin lpf, LogicalPin lpr, bool invert) { - const bool ok1 = spindleForwardPort.Set(lpf, PinAccess::pwm); + const bool ok1 = spindleForwardPort.Set(lpf, PinAccess::pwm, invert); if (lpr == NoLogicalPin) { spindleReversePort.Clear(); return ok1; } - const bool ok2 = spindleReversePort.Set(lpr, PinAccess::pwm); + const bool ok2 = spindleReversePort.Set(lpr, PinAccess::pwm, invert); return ok1 && ok2; } -void Platform::GetSpindlePins(LogicalPin& lpf, LogicalPin& lpr) const +void Platform::GetSpindlePins(LogicalPin& lpf, LogicalPin& lpr, bool& invert) const { - lpf = spindleForwardPort.GetLogicalPin(); + lpf = spindleForwardPort.GetLogicalPin(invert); lpr = spindleReversePort.GetLogicalPin(); } @@ -4155,9 +4143,9 @@ void Platform::SetSpindlePwmFrequency(float freq) spindleReversePort.SetFrequency(freq); } -bool Platform::SetLaserPin(LogicalPin lp) +bool Platform::SetLaserPin(LogicalPin lp, bool invert) { - return laserPort.Set(lp, PinAccess::pwm); + return laserPort.Set(lp, PinAccess::pwm, invert); } void Platform::SetLaserPwmFrequency(float freq) @@ -4328,7 +4316,7 @@ bool Platform::ConfigureStallDetection(GCodeBuffer& gb, const StringRef& reply) if (gb.Seen('F')) { seen = true; - const int sgFilter = (gb.GetIValue() == 1); + const bool sgFilter = (gb.GetIValue() == 1); for (size_t drive = 0; drive < numSmartDrivers; ++drive) { if (IsBitSet(drivers, drive)) @@ -4467,6 +4455,17 @@ void Platform::InitI2c() #endif } +#if SAM4E || SAM4S || SAME70 + +// Get a pseudo-random number +uint32_t Platform::Random() +{ + const uint32_t clocks = GetInterruptClocks(); + return clocks ^ uniqueId[0] ^ uniqueId[1] ^ uniqueId[2] ^ uniqueId[3]; +} + +#endif + // Step pulse timer interrupt void STEP_TC_HANDLER() __attribute__ ((hot)); diff --git a/src/Platform.h b/src/Platform.h index 2ce27086..5977b2fa 100644 --- a/src/Platform.h +++ b/src/Platform.h @@ -38,7 +38,7 @@ Licence: GPL #include "Storage/FileData.h" #include "Storage/MassStorage.h" // must be after Pins.h because it needs NumSdCards defined #include "MessageType.h" -#include "Zprobe.h" +#include "ZProbe.h" #include "ZProbeProgrammer.h" #if defined(DUET_NG) @@ -158,6 +158,17 @@ enum class EndStopInputType motorStall = 3 }; +// Other firmware that we might switch to be compatible with. +enum class Compatibility : uint8_t +{ + me = 0, + reprapFirmware = 1, + marlin = 2, + teacup = 3, + sprinter = 4, + repetier = 5 +}; + /***************************************************************************************************/ // Enumeration describing the reasons for a software reset. @@ -329,8 +340,8 @@ public: // Communications and data storage OutputBuffer *GetAuxGCodeReply(); // Returns cached G-Code reply for AUX devices and clears its reference - void AppendAuxReply(OutputBuffer *buf); - void AppendAuxReply(const char *msg); + void AppendAuxReply(OutputBuffer *buf, bool rawMessage); + void AppendAuxReply(const char *msg, bool rawMessage); uint32_t GetAuxSeq() { return auxSeq; } bool HaveAux() const { return auxDetected; } // Any device on the AUX line? void SetAuxDetected() { auxDetected = true; } @@ -434,7 +445,7 @@ public: pre(axis < MaxAxes); uint32_t GetAllEndstopStates() const; - void SetAxisDriversConfig(size_t drive, const AxisDriversConfig& config); + void SetAxisDriversConfig(size_t axis, const AxisDriversConfig& config); const AxisDriversConfig& GetAxisDriversConfig(size_t drive) const { return axisDrivers[drive]; } void SetExtruderDriver(size_t extruder, uint8_t driver); @@ -555,13 +566,13 @@ public: // Logging support bool ConfigureLogging(GCodeBuffer& gb, const StringRef& reply); - // Ancilliary PWM + // Ancillary PWM void SetExtrusionAncilliaryPwmValue(float v); float GetExtrusionAncilliaryPwmValue() const; void SetExtrusionAncilliaryPwmFrequency(float f); float GetExtrusionAncilliaryPwmFrequency() const; - bool SetExtrusionAncilliaryPwmPin(LogicalPin logicalPin); - int GetExtrusionAncilliaryPwmPin() const { return extrusionAncilliaryPwmPort.GetLogicalPin(); } + bool SetExtrusionAncilliaryPwmPin(LogicalPin logicalPin, bool invert); + LogicalPin GetExtrusionAncilliaryPwmPin(bool& invert) const { return extrusionAncilliaryPwmPort.GetLogicalPin(invert); } void ExtrudeOn(); void ExtrudeOff(); @@ -569,19 +580,23 @@ public: void SetSpindlePwm(float pwm); void SetLaserPwm(float pwm); - bool SetSpindlePins(LogicalPin lpf, LogicalPin lpr); - void GetSpindlePins(LogicalPin& lpf, LogicalPin& lpr) const; + bool SetSpindlePins(LogicalPin lpf, LogicalPin lpr, bool invert); + void GetSpindlePins(LogicalPin& lpf, LogicalPin& lpr, bool& invert) const; void SetSpindlePwmFrequency(float freq); float GetSpindlePwmFrequency() const { return spindleForwardPort.GetFrequency(); } - bool SetLaserPin(LogicalPin lp); - LogicalPin GetLaserPin() const { return laserPort.GetLogicalPin(); } + bool SetLaserPin(LogicalPin lp, bool invert); + LogicalPin GetLaserPin(bool& invert) const { return laserPort.GetLogicalPin(invert); } void SetLaserPwmFrequency(float freq); float GetLaserPwmFrequency() const { return laserPort.GetFrequency(); } // Misc void InitI2c(); +#if SAM4E || SAM4S || SAME70 + uint32_t Random(); +#endif + static uint8_t softwareResetDebugInfo; // extra info for debugging #if SAM4S || SAME70 @@ -639,7 +654,7 @@ private: uint32_t icsr; // interrupt control and state register uint32_t bfar; // bus fault address register uint32_t sp; // stack pointer - time_t when; // value of the RTC when the software reset occurred + uint32_t when; // value of the RTC when the software reset occurred uint32_t stack[24]; // stack when the exception occurred, with the program counter at the bottom bool isVacant() const // return true if this struct can be written without erasing it first @@ -672,12 +687,16 @@ private: ZProbe alternateZProbeParameters; // Z probe values for the alternate sensor ZProbeType zProbeType; // the type of Z probe we are currently using - byte ipAddress[4]; - byte netMask[4]; - byte gateWay[4]; + // Network + uint8_t ipAddress[4]; + uint8_t netMask[4]; + uint8_t gateWay[4]; uint8_t defaultMacAddress[6]; - Compatibility compatibility; + // Board and processor +#if SAM4E || SAM4S || SAME70 + uint32_t uniqueId[5]; +#endif BoardType board; #ifdef DUET_NG @@ -687,6 +706,7 @@ private: uint32_t longWait; bool active; + Compatibility compatibility; uint32_t errorCodeBits; void InitialiseInterrupts(); @@ -716,9 +736,6 @@ private: #endif float motorCurrents[DRIVES]; // the normal motor current for each stepper driver float motorCurrentFraction[DRIVES]; // the percentages of normal motor current that each driver is set to -#if HAS_SMART_DRIVERS - float motorStandstillCurrentFraction[DRIVES]; -#endif AxisDriversConfig axisDrivers[MaxAxes]; // the driver numbers assigned to each axis uint8_t extruderDrivers[MaxExtruders]; // the driver number assigned to each extruder uint32_t driveDriverBits[2 * DRIVES]; // the bitmap of driver port bits for each axis or extruder, followed by the raw versions @@ -773,7 +790,7 @@ private: void InitZProbe(); uint16_t GetRawZProbeReading() const; - void UpdateNetworkAddress(byte dst[4], const byte src[4]); + void UpdateNetworkAddress(uint8_t dst[4], const uint8_t src[4]); // Axes and endstops float axisMaxima[MaxAxes]; diff --git a/src/PortControl.cpp b/src/PortControl.cpp index 4cd2be96..7af80de5 100644 --- a/src/PortControl.cpp +++ b/src/PortControl.cpp @@ -85,7 +85,7 @@ bool PortControl::Configure(GCodeBuffer& gb, const StringRef& reply) return true; } IoPort& pm = portMap[i]; - if (!pm.Set((LogicalPin)pnum, PinAccess::write)) + if (!pm.Set((LogicalPin)pnum, PinAccess::write, false)) { reply.printf("Port number %ld is not available", pnum); return true; diff --git a/src/PrintMonitor.cpp b/src/PrintMonitor.cpp index cb00022a..6e857748 100644 --- a/src/PrintMonitor.cpp +++ b/src/PrintMonitor.cpp @@ -345,239 +345,269 @@ bool PrintMonitor::GetFileInfo(const char *directory, const char *fileName, GCod char* const buf = reinterpret_cast<char*>(buf32); size_t sizeToRead, sizeToScan; // number of bytes we want to read and scan in this go - if (parseState == parsingHeader) + switch (parseState) { - bool headerInfoComplete = true; - - // Read a chunk from the header. On the first run only process GCODE_READ_SIZE bytes, but use overlap next times. - sizeToRead = (size_t)min<FilePosition>(fileBeingParsed->Length() - fileBeingParsed->Position(), GCODE_READ_SIZE); - if (fileOverlapLength > 0) - { - memcpy(buf, fileOverlap, fileOverlapLength); - sizeToScan = sizeToRead + fileOverlapLength; - } - else + case parsingHeader: { - sizeToScan = sizeToRead; - } + bool headerInfoComplete = true; - uint32_t startTime = millis(); - const int nbytes = fileBeingParsed->Read(&buf[fileOverlapLength], sizeToRead); - if (nbytes != (int)sizeToRead) - { - platform.MessageF(ErrorMessage, "Failed to read header of G-Code file \"%s\"\n", fileName); - parseState = notParsing; - fileBeingParsed->Close(); - info = parsedFileInfo; - return true; - } - buf[sizeToScan] = 0; + // Read a chunk from the header. On the first run only process GCODE_READ_SIZE bytes, but use overlap next times. + sizeToRead = (size_t)min<FilePosition>(fileBeingParsed->Length() - fileBeingParsed->Position(), GCODE_READ_SIZE); + if (fileOverlapLength > 0) + { + memcpy(buf, fileOverlap, fileOverlapLength); + sizeToScan = sizeToRead + fileOverlapLength; + } + else + { + sizeToScan = sizeToRead; + } - // Record performance data - uint32_t now = millis(); - accumulatedReadTime += now - startTime; - startTime = now; + uint32_t startTime = millis(); + const int nbytes = fileBeingParsed->Read(&buf[fileOverlapLength], sizeToRead); + if (nbytes != (int)sizeToRead) + { + platform.MessageF(ErrorMessage, "Failed to read header of G-Code file \"%s\"\n", fileName); + parseState = notParsing; + fileBeingParsed->Close(); + info = parsedFileInfo; + return true; + } + buf[sizeToScan] = 0; - // Search for filament usage (Cura puts it at the beginning of a G-code file) - if (parsedFileInfo.numFilaments == 0) - { - parsedFileInfo.numFilaments = FindFilamentUsed(buf, sizeToScan, parsedFileInfo.filamentNeeded, DRIVES - reprap.GetGCodes().GetTotalAxes()); - headerInfoComplete &= (parsedFileInfo.numFilaments != 0); - } + // Record performance data + uint32_t now = millis(); + accumulatedReadTime += now - startTime; + startTime = now; - // Look for first layer height - if (parsedFileInfo.firstLayerHeight == 0.0) - { - headerInfoComplete &= FindFirstLayerHeight(buf, sizeToScan, parsedFileInfo.firstLayerHeight); - } + // Search for filament usage (Cura puts it at the beginning of a G-code file) + if (parsedFileInfo.numFilaments == 0) + { + parsedFileInfo.numFilaments = FindFilamentUsed(buf, sizeToScan, parsedFileInfo.filamentNeeded, DRIVES - reprap.GetGCodes().GetTotalAxes()); + headerInfoComplete &= (parsedFileInfo.numFilaments != 0); + } - // Look for layer height - if (parsedFileInfo.layerHeight == 0.0) - { - headerInfoComplete &= FindLayerHeight(buf, sizeToScan, parsedFileInfo.layerHeight); - } + // Look for first layer height + if (parsedFileInfo.firstLayerHeight == 0.0) + { + headerInfoComplete &= FindFirstLayerHeight(buf, sizeToScan, parsedFileInfo.firstLayerHeight); + } - // Look for slicer program - if (parsedFileInfo.generatedBy[0] == 0) - { - static const char * const GeneratedByStrings[] = + // Look for layer height + if (parsedFileInfo.layerHeight == 0.0) { - "generated by ", // slic3r and S3D - ";Sliced by ", // ideaMaker - "; KISSlicer", // KISSlicer - ";Sliced at: ", // Cura (old) - ";Generated with " // Cura (new) - }; - - size_t index = 0; - const char* pos; - do + headerInfoComplete &= FindLayerHeight(buf, sizeToScan, parsedFileInfo.layerHeight); + } + + // Look for slicer program + if (parsedFileInfo.generatedBy[0] == 0) { - pos = strstr(buf, GeneratedByStrings[index]); - if (pos != nullptr) + static const char * const GeneratedByStrings[] = { - break; - } - ++index; - } while (index < ARRAY_SIZE(GeneratedByStrings)); + "generated by ", // slic3r and S3D + ";Sliced by ", // ideaMaker + "; KISSlicer", // KISSlicer + ";Sliced at: ", // Cura (old) + ";Generated with " // Cura (new) + }; + + size_t index = 0; + const char* pos; + do + { + pos = strstr(buf, GeneratedByStrings[index]); + if (pos != nullptr) + { + break; + } + ++index; + } while (index < ARRAY_SIZE(GeneratedByStrings)); - if (pos != nullptr) - { - const char* introString = ""; - switch (index) + if (pos != nullptr) { - default: - pos += strlen(GeneratedByStrings[index]); - break; + const char* introString = ""; + switch (index) + { + default: + pos += strlen(GeneratedByStrings[index]); + break; - case 2: // KISSlicer - pos += 2; - break; + case 2: // KISSlicer + pos += 2; + break; - case 3: // Cura (old) - introString = "Cura at "; - pos += strlen(GeneratedByStrings[index]); - break; + case 3: // Cura (old) + introString = "Cura at "; + pos += strlen(GeneratedByStrings[index]); + break; + } + + strcpy(parsedFileInfo.generatedBy, introString); + size_t i = strlen(introString); + while (i < ARRAY_SIZE(parsedFileInfo.generatedBy) - 1 && *pos >= ' ') + { + parsedFileInfo.generatedBy[i++] = *pos++; + } + parsedFileInfo.generatedBy[i] = 0; } + } + headerInfoComplete &= (parsedFileInfo.generatedBy[0] != 0); + + // Keep track of the time stats + accumulatedParseTime += millis() - startTime; - strcpy(parsedFileInfo.generatedBy, introString); - size_t i = strlen(introString); - while (i < ARRAY_SIZE(parsedFileInfo.generatedBy) - 1 && *pos >= ' ') + // Can we proceed to the footer? Don't scan more than the first 4KB of the file + FilePosition pos = fileBeingParsed->Position(); + if (headerInfoComplete || pos >= GCODE_HEADER_SIZE || pos == fileBeingParsed->Length()) + { + // Yes - see if we need to output some debug info + if (reprap.Debug(modulePrintMonitor)) { - parsedFileInfo.generatedBy[i++] = *pos++; + platform.MessageF(UsbMessage, "Header complete, processed %lu bytes, read time %.3fs, parse time %.3fs\n", + fileBeingParsed->Position(), (double)((float)accumulatedReadTime/1000.0), (double)((float)accumulatedParseTime/1000.0)); } - parsedFileInfo.generatedBy[i] = 0; + + // Go to the last chunk and proceed from there on + const FilePosition seekFromEnd = ((fileBeingParsed->Length() - 1) % GCODE_READ_SIZE) + 1; + nextSeekPos = fileBeingParsed->Length() - seekFromEnd; + accumulatedSeekTime = accumulatedReadTime = accumulatedParseTime = 0; + fileOverlapLength = 0; + parseState = seeking; + } + else + { + // No - copy the last chunk of the buffer for overlapping search + fileOverlapLength = min<size_t>(sizeToRead, GCODE_OVERLAP_SIZE); + memcpy(fileOverlap, &buf[sizeToRead - fileOverlapLength], fileOverlapLength); } } - headerInfoComplete &= (parsedFileInfo.generatedBy[0] != 0); - - // Keep track of the time stats - accumulatedParseTime += millis() - startTime; + break; - // Can we proceed to the footer? Don't scan more than the first 4KB of the file - FilePosition pos = fileBeingParsed->Position(); - if (headerInfoComplete || pos >= GCODE_HEADER_SIZE || pos == fileBeingParsed->Length()) + case seeking: + // Seeking into a large file can take a long time using the FAT file system, so do it in stages { - // Yes - see if we need to output some debug info - if (reprap.Debug(modulePrintMonitor)) + FilePosition currentPos = fileBeingParsed->Position(); + const uint32_t clsize = fileBeingParsed->ClusterSize(); + if (currentPos/clsize > nextSeekPos/clsize) { - platform.MessageF(UsbMessage, "Header complete, processed %lu bytes, read time %.3fs, parse time %.3fs\n", - fileBeingParsed->Position(), (double)((float)accumulatedReadTime/1000.0), (double)((float)accumulatedParseTime/1000.0)); + // Seeking backwards over a cluster boundary, so in practice the seek will start from the start of the file + currentPos = 0; } - // Go to the last chunk and proceed from there on - startTime = millis(); - const FilePosition seekFromEnd = ((fileBeingParsed->Length() - 1) % GCODE_READ_SIZE) + 1; - fileBeingParsed->Seek(fileBeingParsed->Length() - seekFromEnd); - accumulatedSeekTime = millis() - startTime; - accumulatedReadTime = accumulatedParseTime = 0; - fileOverlapLength = 0; - parseState = parsingFooter; - } - else - { - // No - copy the last chunk of the buffer for overlapping search - fileOverlapLength = min<size_t>(sizeToRead, GCODE_OVERLAP_SIZE); - memcpy(fileOverlap, &buf[sizeToRead - fileOverlapLength], fileOverlapLength); - } - } + // Seek at most 512 clusters at a time + const FilePosition maxSeekDistance = 512 * (FilePosition)clsize; + const bool doFullSeek = (nextSeekPos <= currentPos) || (nextSeekPos - currentPos <= maxSeekDistance); + const FilePosition thisSeekPos = (doFullSeek) ? nextSeekPos : currentPos + maxSeekDistance; - if (parseState == parsingFooter) - { - // Processing the footer. See how many bytes we need to read and if we can reuse the overlap - FilePosition pos = fileBeingParsed->Position(); - sizeToRead = (size_t)min<FilePosition>(fileBeingParsed->Length() - pos, GCODE_READ_SIZE); - if (fileOverlapLength > 0) - { - memcpy(&buf[sizeToRead], fileOverlap, fileOverlapLength); - sizeToScan = sizeToRead + fileOverlapLength; - } - else - { - sizeToScan = sizeToRead; + const uint32_t startTime = millis(); + if (!fileBeingParsed->Seek(thisSeekPos)) + { + platform.Message(ErrorMessage, "Could not seek from end of file!\n"); + parseState = notParsing; + fileBeingParsed->Close(); + info = parsedFileInfo; + return true; + } + accumulatedSeekTime += millis() - startTime; + if (doFullSeek) + { + parseState = parsingFooter; + } } + break; - // Read another chunk from the footer - uint32_t startTime = millis(); - int nbytes = fileBeingParsed->Read(buf, sizeToRead); - if (nbytes != (int)sizeToRead) + case parsingFooter: { - platform.MessageF(ErrorMessage, "Failed to read footer from G-Code file \"%s\"\n", fileName); - parseState = notParsing; - fileBeingParsed->Close(); - info = parsedFileInfo; - return true; - } - buf[sizeToScan] = 0; + // Processing the footer. See how many bytes we need to read and if we can reuse the overlap + FilePosition pos = fileBeingParsed->Position(); + sizeToRead = (size_t)min<FilePosition>(fileBeingParsed->Length() - pos, GCODE_READ_SIZE); + if (fileOverlapLength > 0) + { + memcpy(&buf[sizeToRead], fileOverlap, fileOverlapLength); + sizeToScan = sizeToRead + fileOverlapLength; + } + else + { + sizeToScan = sizeToRead; + } - // Record performance data - uint32_t now = millis(); - accumulatedReadTime += now - startTime; - startTime = now; + // Read another chunk from the footer + uint32_t startTime = millis(); + int nbytes = fileBeingParsed->Read(buf, sizeToRead); + if (nbytes != (int)sizeToRead) + { + platform.MessageF(ErrorMessage, "Failed to read footer from G-Code file \"%s\"\n", fileName); + parseState = notParsing; + fileBeingParsed->Close(); + info = parsedFileInfo; + return true; + } + buf[sizeToScan] = 0; - bool footerInfoComplete = true; + // Record performance data + uint32_t now = millis(); + accumulatedReadTime += now - startTime; + startTime = now; - // Search for filament used - if (parsedFileInfo.numFilaments == 0) - { - parsedFileInfo.numFilaments = FindFilamentUsed(buf, sizeToScan, parsedFileInfo.filamentNeeded, DRIVES - reprap.GetGCodes().GetTotalAxes()); + bool footerInfoComplete = true; + + // Search for filament used if (parsedFileInfo.numFilaments == 0) { - footerInfoComplete = false; + parsedFileInfo.numFilaments = FindFilamentUsed(buf, sizeToScan, parsedFileInfo.filamentNeeded, DRIVES - reprap.GetGCodes().GetTotalAxes()); + if (parsedFileInfo.numFilaments == 0) + { + footerInfoComplete = false; + } } - } - // Search for layer height - if (parsedFileInfo.layerHeight == 0.0) - { - if (!FindLayerHeight(buf, sizeToScan, parsedFileInfo.layerHeight)) + // Search for layer height + if (parsedFileInfo.layerHeight == 0.0) { - footerInfoComplete = false; + if (!FindLayerHeight(buf, sizeToScan, parsedFileInfo.layerHeight)) + { + footerInfoComplete = false; + } } - } - // Search for object height - if (parsedFileInfo.objectHeight == 0.0) - { - if (!FindHeight(buf, sizeToScan, parsedFileInfo.objectHeight)) + // Search for object height + if (parsedFileInfo.objectHeight == 0.0) { - footerInfoComplete = false; + if (!FindHeight(buf, sizeToScan, parsedFileInfo.objectHeight)) + { + footerInfoComplete = false; + } } - } - // Keep track of the time stats - accumulatedParseTime += millis() - startTime; + // Keep track of the time stats + accumulatedParseTime += millis() - startTime; - // If we've collected all details, scanned the last 192K of the file or if we cannot go any further, stop here. - if (footerInfoComplete || pos == 0 || fileBeingParsed->Length() - pos >= GCODE_FOOTER_SIZE) - { - if (reprap.Debug(modulePrintMonitor)) + // If we've collected all details, scanned the last 192K of the file or if we cannot go any further, stop here. + if (footerInfoComplete || pos == 0 || fileBeingParsed->Length() - pos >= GCODE_FOOTER_SIZE) { - platform.MessageF(UsbMessage, "Footer complete, processed %lu bytes, read time %.3fs, parse time %.3fs, seek time %.3fs\n", - fileBeingParsed->Length() - fileBeingParsed->Position() + GCODE_READ_SIZE, - (double)((float)accumulatedReadTime/1000.0), (double)((float)accumulatedParseTime/1000.0), (double)((float)accumulatedSeekTime/1000.0)); + if (reprap.Debug(modulePrintMonitor)) + { + platform.MessageF(UsbMessage, "Footer complete, processed %lu bytes, read time %.3fs, parse time %.3fs, seek time %.3fs\n", + fileBeingParsed->Length() - fileBeingParsed->Position() + GCODE_READ_SIZE, + (double)((float)accumulatedReadTime/1000.0), (double)((float)accumulatedParseTime/1000.0), (double)((float)accumulatedSeekTime/1000.0)); + } + parseState = notParsing; + fileBeingParsed->Close(); + info = parsedFileInfo; + return true; } - parseState = notParsing; - fileBeingParsed->Close(); - info = parsedFileInfo; - return true; - } - // Else go back further - startTime = millis(); - size_t seekOffset = (size_t)min<FilePosition>(pos, GCODE_READ_SIZE); - if (!fileBeingParsed->Seek(pos - seekOffset)) - { - platform.Message(ErrorMessage, "Could not seek from end of file!\n"); - parseState = notParsing; - fileBeingParsed->Close(); - info = parsedFileInfo; - return true; + // Else go back further + fileOverlapLength = (size_t)min<FilePosition>(sizeToScan, GCODE_OVERLAP_SIZE); + memcpy(fileOverlap, buf, fileOverlapLength); + nextSeekPos = (pos <= GCODE_READ_SIZE) ? 0 : pos - GCODE_READ_SIZE; + parseState = seeking; } - accumulatedSeekTime += millis() - startTime; + break; - fileOverlapLength = (size_t)min<FilePosition>(sizeToScan, GCODE_OVERLAP_SIZE); - memcpy(fileOverlap, buf, fileOverlapLength); + default: // should not get here + info = parsedFileInfo; + return true; } } while (!isPrinting && millis() - loopStartTime < MAX_FILEINFO_PROCESS_TIME); return false; @@ -1057,7 +1087,7 @@ bool PrintMonitor::FindLayerHeight(const char *buf, size_t len, float& layerHeig // Scan the buffer for the filament used. The buffer is null-terminated. // Returns the number of filaments found. -unsigned int PrintMonitor::FindFilamentUsed(const char* buf, size_t len, float *filamentUsed, unsigned int maxFilaments) const +unsigned int PrintMonitor::FindFilamentUsed(const char* buf, size_t len, float *filamentUsed, size_t maxFilaments) const { unsigned int filamentsFound = 0; @@ -1159,7 +1189,7 @@ unsigned int PrintMonitor::FindFilamentUsed(const char* buf, size_t len, float * if (p != nullptr) { const float filamentCMM = strtof(p + strlen(filamentVolumeStr), nullptr) * 1000.0; - filamentUsed[filamentsFound++] = filamentCMM / (PI * (platform.GetFilamentWidth() / 2.0) * (platform.GetFilamentWidth() / 2.0)); + filamentUsed[filamentsFound++] = filamentCMM / (Pi * fsquare(platform.GetFilamentWidth() / 2.0)); } } diff --git a/src/PrintMonitor.h b/src/PrintMonitor.h index f94e4f7f..4f1cb56d 100644 --- a/src/PrintMonitor.h +++ b/src/PrintMonitor.h @@ -68,6 +68,7 @@ enum FileParseState { notParsing, parsingHeader, + seeking, parsingFooter }; @@ -129,9 +130,10 @@ class PrintMonitor float layerEstimatedTimeLeft; // We parse G-Code files in multiple stages. These variables hold the required information - volatile FileParseState parseState; + FileParseState parseState; char filenameBeingParsed[MaxFilenameLength]; FileStore *fileBeingParsed; + FilePosition nextSeekPos; GCodeFileInfo parsedFileInfo; char fileOverlap[GCODE_OVERLAP_SIZE]; @@ -145,7 +147,7 @@ class PrintMonitor bool FindHeight(const char* buf, size_t len, float& height) const; bool FindFirstLayerHeight(const char* buf, size_t len, float& layerHeight) const; bool FindLayerHeight(const char* buf, size_t len, float& layerHeight) const; - unsigned int FindFilamentUsed(const char* buf, size_t len, float *filamentUsed, unsigned int maxFilaments) const; + unsigned int FindFilamentUsed(const char* buf, size_t len, float *filamentUsed, size_t maxFilaments) const; uint32_t accumulatedParseTime, accumulatedReadTime, accumulatedSeekTime; }; diff --git a/src/RepRap.cpp b/src/RepRap.cpp index 39ec4dc5..5a486c2c 100644 --- a/src/RepRap.cpp +++ b/src/RepRap.cpp @@ -102,7 +102,7 @@ void RepRap::Init() // All of the following init functions must execute reasonably quickly before the watchdog times us out platform->Init(); network->Init(); - SetName(DEFAULT_MACHINE_NAME); // network must be initialised before calling this because it calls SetHostName + SetName(DEFAULT_MACHINE_NAME); // network must be initialised before calling this because this calls SetHostName gCodes->Init(); move->Init(); heat->Init(); @@ -1692,9 +1692,12 @@ char RepRap::GetStatusCharacter() const : (gCodes->IsResuming()) ? 'R' // Resuming : (gCodes->IsDoingToolChange()) ? 'T' // Changing tool : (gCodes->IsPaused()) ? 'S' // Paused / Stopped - : (printMonitor->IsPrinting()) ? 'P' // Printing + : (printMonitor->IsPrinting()) + ? ((gCodes->IsSimulating()) ? 'M' // Simulating + : 'P' // Printing + ) : (gCodes->DoingFileMacro() || !move->NoLiveMovement()) ? 'B' // Busy - : 'I'; // Idle + : 'I'; // Idle } bool RepRap::NoPasswordSet() const diff --git a/src/RepRapFirmware.h b/src/RepRapFirmware.h index 8764ddcb..b44149a8 100644 --- a/src/RepRapFirmware.h +++ b/src/RepRapFirmware.h @@ -154,6 +154,9 @@ private: const T _end; }; +// Macro to create a SimpleRange from an array +#define ARRAY_INDICES(_arr) (SimpleRange<size_t>(ARRAY_SIZE(_arr))) + // Helper functions to work on bitmaps of various lengths. // The primary purpose of these is to allow us to switch between 16, 32 and 64-bit bitmaps. @@ -202,9 +205,6 @@ template<typename BitmapType> BitmapType UnsignedArrayToBitMap(const uint32_t *a return res; } -// Macro to create a SimpleRange from an array -#define ARRAY_INDICES(_arr) (SimpleRange<size_t>(ARRAY_SIZE(_arr))) - // A string buffer used for temporary purposes extern StringRef scratchString; @@ -221,8 +221,10 @@ constexpr float SecondsToMinutes = 1.0/MinutesToSeconds; constexpr float SecondsToMillis = 1000.0; constexpr float MillisToSeconds = 0.001; constexpr float InchToMm = 25.4; -constexpr float DegreesToRadians = PI/180.0; -constexpr float RadiansToDegrees = 180.0/PI; +constexpr float Pi = 3.141592653589793; +constexpr float TwoPi = 3.141592653589793 * 2; +constexpr float DegreesToRadians = 3.141592653589793/180.0; +constexpr float RadiansToDegrees = 180.0/3.141592653589793; #define DEGREE_SYMBOL "\xC2\xB0" // degree-symbol encoding in UTF8 diff --git a/src/Storage/FileStore.cpp b/src/Storage/FileStore.cpp index bb8cd07a..652c78d4 100644 --- a/src/Storage/FileStore.cpp +++ b/src/Storage/FileStore.cpp @@ -205,7 +205,12 @@ bool FileStore::Seek(FilePosition pos) FilePosition FileStore::Position() const { - return file.fptr; + return (inUse) ? file.fptr : 0; +} + +uint32_t FileStore::ClusterSize() const +{ + return (inUse) ? file.fs->csize * 512u : 1; // we divide by the cluster size so return 1 not 0 if there is an error } #if 0 // not currently used diff --git a/src/Storage/FileStore.h b/src/Storage/FileStore.h index ed62d77c..5651b0bd 100644 --- a/src/Storage/FileStore.h +++ b/src/Storage/FileStore.h @@ -34,10 +34,12 @@ public: bool ForceClose(); bool Seek(FilePosition pos); // Jump to pos in the file FilePosition Position() const; // Return the current position in the file, assuming we are reading the file + uint32_t ClusterSize() const; // Cluster size in bytes + FilePosition Length() const; // File size in bytes #if 0 // not currently used bool GoToEnd(); // Position the file at the end (so you can write on the end). #endif - FilePosition Length() const; // File size in bytes + void Duplicate(); // Create a second reference to this file bool Flush(); // Write remaining buffer data bool Invalidate(const FATFS *fs, bool doClose); // Invalidate the file if it uses the specified FATFS object diff --git a/src/Storage/MassStorage.cpp b/src/Storage/MassStorage.cpp index 7a0e6afd..ba167588 100644 --- a/src/Storage/MassStorage.cpp +++ b/src/Storage/MassStorage.cpp @@ -653,7 +653,7 @@ void MassStorage::Spin() } // Get information about the SD card and interface speed -MassStorage::InfoResult MassStorage::GetCardInfo(size_t slot, uint64_t& capacity, uint64_t& freeSpace, uint32_t& speed) +MassStorage::InfoResult MassStorage::GetCardInfo(size_t slot, uint64_t& capacity, uint64_t& freeSpace, uint32_t& speed, uint32_t& clSize) { if (slot >= NumSdCards) { @@ -673,7 +673,16 @@ MassStorage::InfoResult MassStorage::GetCardInfo(size_t slot, uint64_t& capacity uint32_t freeClusters; FATFS *fs; const FRESULT fr = f_getfree(path.c_str(), &freeClusters, &fs); - freeSpace = (fr == FR_OK) ? (uint64_t)freeClusters * fs->csize * 512 : 0; + if (fr == FR_OK) + { + clSize = fs->csize * 512; + freeSpace = (fr == FR_OK) ? (uint64_t)freeClusters * clSize : 0; + } + else + { + clSize = 0; + freeSpace = 0; + } return InfoResult::ok; } diff --git a/src/Storage/MassStorage.h b/src/Storage/MassStorage.h index 68f29058..42302f74 100644 --- a/src/Storage/MassStorage.h +++ b/src/Storage/MassStorage.h @@ -54,7 +54,7 @@ public: ok = 2 }; - InfoResult GetCardInfo(size_t slot, uint64_t& capacity, uint64_t& freeSpace, uint32_t& speed); + InfoResult GetCardInfo(size_t slot, uint64_t& capacity, uint64_t& freeSpace, uint32_t& speed, uint32_t& clSize); friend class Platform; friend class FileStore; diff --git a/src/Version.h b/src/Version.h index 0cb0295e..53dc216f 100644 --- a/src/Version.h +++ b/src/Version.h @@ -9,11 +9,11 @@ #define SRC_VERSION_H_ #ifndef VERSION -# define VERSION "1.21RC2" +# define VERSION "1.21RC3" #endif #ifndef DATE -# define DATE "2018-02-15 build 2" +# define DATE "2018-02-28 build 4" #endif #define AUTHORS "reprappro, dc42, chrishamm, t3p3, dnewman" |