diff options
author | David Crocker <dcrocker@eschertech.com> | 2018-04-19 19:54:05 +0300 |
---|---|---|
committer | David Crocker <dcrocker@eschertech.com> | 2018-04-19 19:54:28 +0300 |
commit | d51ad4c5cbfef83a9b9aaa5b79a839380660d2e6 (patch) | |
tree | 938d033b032f0efbb9fb3a902e5cdf044c6914e6 | |
parent | 57cb9443a92b746e5c290c0e9170cad3963bc598 (diff) |
Version 2.0beta2
Bug fixes:
DWC sometimes disconnected after uploading a GCode file
Reverted the behaviour of G0 commands to the pre-2.0 behaviour when the
machine mode is FFF (i.e. the F parameter is recognised and the feed
rate is shared with the G1 feed rate)
If a G1 command with extrusion was followed by a G0 command, the
extrusion was repeated in the G0 command
When high microstepping was used, certain sequences of movement commands
could lock up the movement system
38 files changed, 425 insertions, 205 deletions
@@ -563,7 +563,6 @@ <listOptionValue builtIn="false" value=""${workspace_loc:/${ProjName}/src}""/> <listOptionValue builtIn="false" value=""${workspace_loc:/${ProjName}/src/DuetM}""/> <listOptionValue builtIn="false" value=""${workspace_loc:/${ProjName}/src/Networking}""/> - <listOptionValue builtIn="false" value=""${workspace_loc:/FreeRTOS/src/include}""/> </option> <option id="gnu.cpp.compiler.option.preprocessor.def.1565207565" name="Defined symbols (-D)" superClass="gnu.cpp.compiler.option.preprocessor.def" useByScannerDiscovery="false" valueType="definedSymbols"> <listOptionValue builtIn="false" value="__SAM4S8C__"/> @@ -691,7 +690,6 @@ <listOptionValue builtIn="false" value=""${workspace_loc:/${ProjName}/src/Networking/LwipEthernet}""/> <listOptionValue builtIn="false" value=""${workspace_loc:/${ProjName}/src/Networking/LwipEthernet/Lwip/src/include}""/> <listOptionValue builtIn="false" value=""${workspace_loc:/DuetWiFiSocketServer/src/include}""/> - <listOptionValue builtIn="false" value=""${workspace_loc:/FreeRTOS/src/include}""/> </option> <option id="gnu.cpp.compiler.option.preprocessor.def.178336065" name="Defined symbols (-D)" superClass="gnu.cpp.compiler.option.preprocessor.def" useByScannerDiscovery="false" valueType="definedSymbols"> <listOptionValue builtIn="false" value="__SAME70Q21__"/> @@ -950,6 +948,140 @@ </storageModule> <storageModule moduleId="org.eclipse.cdt.core.externalSettings"/> </cconfiguration> + <cconfiguration id="cdt.managedbuild.config.gnu.cross.exe.release.516195201.976458850.241502451.1275216290.274082366.1645191116.1852610203"> + <storageModule buildSystemId="org.eclipse.cdt.managedbuilder.core.configurationDataProvider" id="cdt.managedbuild.config.gnu.cross.exe.release.516195201.976458850.241502451.1275216290.274082366.1645191116.1852610203" moduleId="org.eclipse.cdt.core.settings" name="SAME70_RTOS"> + <macros> + <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"/> + </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="SAME70Firmware" 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.274082366.1645191116.1852610203" name="SAME70_RTOS" parent="cdt.managedbuild.config.gnu.cross.exe.release" postannouncebuildStep="Generating binary file" postbuildStep="arm-none-eabi-objcopy -O binary ${workspace_loc:/${ProjName}/${ConfigName}}/SAME70Firmware.elf ${workspace_loc:/${ProjName}/${ConfigName}}/SAME70Firmware.bin"> + <folderInfo id="cdt.managedbuild.config.gnu.cross.exe.release.516195201.976458850.241502451.1275216290.274082366.1645191116.1852610203." name="/" resourcePath=""> + <toolChain id="cdt.managedbuild.toolchain.gnu.cross.exe.release.5959303" name="Cross GCC" superClass="cdt.managedbuild.toolchain.gnu.cross.exe.release"> + <option id="cdt.managedbuild.option.gnu.cross.path.163568524" name="Path" superClass="cdt.managedbuild.option.gnu.cross.path" useByScannerDiscovery="false" value="${GccPath}" valueType="string"/> + <option id="cdt.managedbuild.option.gnu.cross.prefix.308380201" 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.1827418537" isAbstract="false" osList="all" superClass="cdt.managedbuild.targetPlatform.gnu.cross"/> + <builder buildPath="${workspace_loc:/RepRapFirmware}/Release" id="cdt.managedbuild.builder.gnu.cross.1828958094" 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.254554862" name="Cross GCC Assembler" superClass="cdt.managedbuild.tool.gnu.cross.assembler"> + <inputType id="cdt.managedbuild.tool.gnu.assembler.input.1960931313" 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.1113168108" 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.1099089925" 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.2018591546" name="Debug Level" superClass="gnu.c.compiler.option.debugging.level" useByScannerDiscovery="false" value="gnu.c.debugging.level.default" valueType="enumerated"/> + <option id="gnu.c.compiler.option.misc.verbose.1767118602" name="Verbose (-v)" superClass="gnu.c.compiler.option.misc.verbose" useByScannerDiscovery="false" value="false" valueType="boolean"/> + <option id="gnu.c.compiler.option.misc.other.2139236731" name="Other flags" superClass="gnu.c.compiler.option.misc.other" useByScannerDiscovery="false" value="-c -std=gnu99 -mcpu=cortex-m7 -mthumb -mfpu=fpv5-d16 -mfloat-abi=hard -ffunction-sections -fdata-sections -nostdlib -Wdouble-promotion -fsingle-precision-constant" valueType="string"/> + <option id="gnu.c.compiler.option.include.paths.1736169055" 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/clock}""/> + <listOptionValue builtIn="false" value=""${workspace_loc:/${CoreName}/asf/common/services/ioport}""/> + <listOptionValue builtIn="false" value=""${workspace_loc:/${CoreName}/asf/sam/components/ethernet_phy/ksz8081rna}""/> + <listOptionValue builtIn="false" value=""${workspace_loc:/${CoreName}/asf/sam/drivers/hsmci}""/> + <listOptionValue builtIn="false" value=""${workspace_loc:/${CoreName}/asf/sam/drivers/gmac}""/> + <listOptionValue builtIn="false" value=""${workspace_loc:/${CoreName}/asf/sam/drivers/pmc}""/> + <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/same70/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/same70}""/> + <listOptionValue builtIn="false" value=""${workspace_loc:/${ProjName}/src/SAME70_TEST}""/> + <listOptionValue builtIn="false" value=""${workspace_loc:/${ProjName}/src/Networking/LwipEthernet}""/> + <listOptionValue builtIn="false" value=""${workspace_loc:/${ProjName}/src/Networking/LwipEthernet/Lwip/src/include}""/> + </option> + <option id="gnu.c.compiler.option.preprocessor.def.symbols.316510289" name="Defined symbols (-D)" superClass="gnu.c.compiler.option.preprocessor.def.symbols" useByScannerDiscovery="false" valueType="definedSymbols"> + <listOptionValue builtIn="false" value="__SAME70Q21__"/> + <listOptionValue builtIn="false" value="RTOS"/> + <listOptionValue builtIn="false" value="SAME70_TEST_BOARD"/> + </option> + <option id="gnu.c.compiler.option.dialect.std.133148413" name="Language standard" superClass="gnu.c.compiler.option.dialect.std" useByScannerDiscovery="true" value="gnu.c.compiler.dialect.default" valueType="enumerated"/> + <inputType id="cdt.managedbuild.tool.gnu.c.compiler.input.477491021" superClass="cdt.managedbuild.tool.gnu.c.compiler.input"/> + </tool> + <tool id="cdt.managedbuild.tool.gnu.cross.c.linker.1392905935" name="Cross GCC Linker" superClass="cdt.managedbuild.tool.gnu.cross.c.linker"/> + <tool id="cdt.managedbuild.tool.gnu.cross.archiver.733829747" 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}/SAME70/cores/arduino/syscalls.o" ${INPUTS} ${LinkFlags2}" id="cdt.managedbuild.tool.gnu.cross.cpp.linker.1019421301" name="Cross G++ Linker" superClass="cdt.managedbuild.tool.gnu.cross.cpp.linker"> + <option id="gnu.cpp.link.option.nostdlibs.1609488418" 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.579521002" name="Library search path (-L)" superClass="gnu.cpp.link.option.paths" useByScannerDiscovery="false" valueType="libPaths"> + <listOptionValue builtIn="false" value=""${workspace_loc:/${CoreName}/SAME70_RTOS/}""/> + <listOptionValue builtIn="false" value=""${workspace_loc:/FreeRTOS/SAME70}""/> + </option> + <option id="gnu.cpp.link.option.libs.1783235457" name="Libraries (-l)" superClass="gnu.cpp.link.option.libs" useByScannerDiscovery="false" valueType="libs"> + <listOptionValue builtIn="false" value="${CoreName}"/> + <listOptionValue builtIn="false" value="FreeRTOS"/> + </option> + <option id="gnu.cpp.link.option.flags.2100826215" 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/same70/linker_scripts/gcc/flash.ld} -Wl,-Map,${workspace_loc:/${ProjName}/${ConfigName}}/${BuildArtifactFileBaseName}.map" valueType="string"/> + <inputType id="cdt.managedbuild.tool.gnu.cpp.linker.input.1623645672" 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.1243015316" name="Cross G++ Compiler" superClass="cdt.managedbuild.tool.gnu.cross.cpp.compiler"> + <option id="gnu.cpp.compiler.option.optimization.level.744605431" 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.1247470383" name="Debug Level" superClass="gnu.cpp.compiler.option.debugging.level" useByScannerDiscovery="false" value="gnu.cpp.compiler.debugging.level.default" valueType="enumerated"/> + <option id="gnu.cpp.compiler.option.other.verbose.1130347909" name="Verbose (-v)" superClass="gnu.cpp.compiler.option.other.verbose" useByScannerDiscovery="false" value="false" valueType="boolean"/> + <option id="gnu.cpp.compiler.option.other.other.1453375027" name="Other flags" superClass="gnu.cpp.compiler.option.other.other" useByScannerDiscovery="false" value="-c -std=gnu++14 -mcpu=cortex-m7 -mthumb -mfpu=fpv5-d16 -mfloat-abi=hard -ffunction-sections -fdata-sections -fno-threadsafe-statics -fno-rtti -fno-exceptions -nostdlib -Wdouble-promotion -fsingle-precision-constant" valueType="string"/> + <option id="gnu.cpp.compiler.option.include.paths.633679617" 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/drivers/gmac}""/> + <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/same70/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/same70}""/> + <listOptionValue builtIn="false" value=""${workspace_loc:/${ProjName}/src}""/> + <listOptionValue builtIn="false" value=""${workspace_loc:/${ProjName}/src/SAME70_TEST}""/> + <listOptionValue builtIn="false" value=""${workspace_loc:/${ProjName}/src/Networking}""/> + <listOptionValue builtIn="false" value=""${workspace_loc:/${ProjName}/src/Networking/LwipEthernet}""/> + <listOptionValue builtIn="false" value=""${workspace_loc:/${ProjName}/src/Networking/LwipEthernet/Lwip/src/include}""/> + <listOptionValue builtIn="false" value=""${workspace_loc:/DuetWiFiSocketServer/src/include}""/> + <listOptionValue builtIn="false" value=""${workspace_loc:/FreeRTOS/src/include}""/> + <listOptionValue builtIn="false" value=""${workspace_loc:/FreeRTOS/src/portable/GCC/ARM_CM7/r0p1}""/> + </option> + <option id="gnu.cpp.compiler.option.preprocessor.def.315745995" name="Defined symbols (-D)" superClass="gnu.cpp.compiler.option.preprocessor.def" useByScannerDiscovery="false" valueType="definedSymbols"> + <listOptionValue builtIn="false" value="__SAME70Q21__"/> + <listOptionValue builtIn="false" value="RTOS"/> + <listOptionValue builtIn="false" value="SAME70_TEST_BOARD"/> + <listOptionValue builtIn="false" value="_XOPEN_SOURCE"/> + </option> + <option id="gnu.cpp.compiler.option.dialect.std.815297330" name="Language standard" superClass="gnu.cpp.compiler.option.dialect.std" useByScannerDiscovery="true" value="gnu.cpp.compiler.dialect.default" valueType="enumerated"/> + <inputType id="cdt.managedbuild.tool.gnu.cpp.compiler.input.2035099195" superClass="cdt.managedbuild.tool.gnu.cpp.compiler.input"/> + </tool> + </toolChain> + </folderInfo> + <sourceEntries> + <entry excluding="src/Networking/W5500Ethernet|src/DuetNG/DuetWiFi|src/Duet|src/DuetNG/DuetEthernet/Wiznet/Internet/SNTP|src/DuetNG|src/Networking/LwipEthernet/Lwip/test|src/DuetNG/DuetEthernet/Wiznet/Internet/DNS|src/DuetNG/DuetEthernet/Wiznet/Application|src/DuetNG/DuetEthernet/Wiznet/Internet/MQTT|src/Alligator|src/Display|src/Networking/LwipEthernet/Lwip/src/apps/mqtt|src/Networking/LwipEthernet/Lwip/doc|src/DuetNG/DuetEthernet/Wiznet/Internet/TFTP|src/DuetNG/DuetEthernet/Ethernet3|src/Networking/LwipEthernet/Lwip/src/apps/snmp|src/Networking/LwipEthernet/Lwip/src/apps/httpd|src/DuetNG/DuetEthernet/Wiznet/Internet/FTPServer|src/DuetNG/DuetEthernet/Ethernet3/examples|src/Networking/LwipEthernet/Lwip/src/apps/tftp|src/Networking/LwipEthernet/Lwip/src/netif/ppp|src/Networking/LwipEthernet/Lwip/src/apps/lwiperf|src/DuetNG/DuetEthernet/Wiznet/Internet/FTPClient|src/Networking/LwipEthernet/Lwip/src/apps/sntp|src/DuetNG/DuetEthernet/Wiznet/Internet/httpServer|src/DuetNG/DuetEthernet/Wiznet/Internet/SNMP|src/DuetM|src/RADDS" flags="VALUE_WORKSPACE_PATH|RESOLVED" kind="sourcePath" name=""/> + </sourceEntries> + </configuration> + </storageModule> + <storageModule moduleId="org.eclipse.cdt.core.externalSettings"/> + </cconfiguration> </storageModule> <storageModule moduleId="cdtBuildSystem" version="4.0.0"> <project id="RepRapFirmware.cdt.managedbuild.target.gnu.cross.exe.1494358155" name="Executable" projectType="cdt.managedbuild.target.gnu.cross.exe"/> diff --git a/.settings/language.settings.xml b/.settings/language.settings.xml index da7dcfe5..938a42a5 100644 --- a/.settings/language.settings.xml +++ b/.settings/language.settings.xml @@ -5,7 +5,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="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"> + <provider class="org.eclipse.cdt.internal.build.crossgcc.CrossGCCBuiltinSpecsDetector" console="false" env-hash="1246945069233179866" 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> @@ -16,7 +16,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="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"> + <provider class="org.eclipse.cdt.internal.build.crossgcc.CrossGCCBuiltinSpecsDetector" console="false" env-hash="1246945069233179866" 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,7 +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="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"> + <provider class="org.eclipse.cdt.internal.build.crossgcc.CrossGCCBuiltinSpecsDetector" console="false" env-hash="1246945069233179866" 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> @@ -38,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="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"> + <provider class="org.eclipse.cdt.internal.build.crossgcc.CrossGCCBuiltinSpecsDetector" console="false" env-hash="1246945069233179866" 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 +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="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"> + <provider class="org.eclipse.cdt.internal.build.crossgcc.CrossGCCBuiltinSpecsDetector" console="false" env-hash="1246945069233179866" 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 +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="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"> + <provider class="org.eclipse.cdt.internal.build.crossgcc.CrossGCCBuiltinSpecsDetector" console="false" env-hash="1246945069233179866" 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 +71,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="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"> + <provider class="org.eclipse.cdt.internal.build.crossgcc.CrossGCCBuiltinSpecsDetector" console="false" env-hash="1246945069233179866" 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> @@ -82,7 +82,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="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"> + <provider class="org.eclipse.cdt.internal.build.crossgcc.CrossGCCBuiltinSpecsDetector" console="false" env-hash="1246945069233179866" 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.274082366.1645191116.1852610203" name="SAME70_RTOS"> + <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="1246945069233179866" 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/Duet2CombinedFirmware-2.0b1.bin b/EdgeRelease/Duet2CombinedFirmware-2.0b1.bin Binary files differdeleted file mode 100644 index 58974145..00000000 --- a/EdgeRelease/Duet2CombinedFirmware-2.0b1.bin +++ /dev/null diff --git a/EdgeRelease/Duet2CombinedFirmware.bin b/EdgeRelease/Duet2CombinedFirmware.bin Binary files differindex 2060a467..73bbd3ed 100644 --- a/EdgeRelease/Duet2CombinedFirmware.bin +++ b/EdgeRelease/Duet2CombinedFirmware.bin diff --git a/EdgeRelease/DuetMaestroFirmware-2.0b1.bin b/EdgeRelease/DuetMaestroFirmware-2.0b1.bin Binary files differdeleted file mode 100644 index c88484fc..00000000 --- a/EdgeRelease/DuetMaestroFirmware-2.0b1.bin +++ /dev/null diff --git a/EdgeRelease/DuetMaestroFirmware.bin b/EdgeRelease/DuetMaestroFirmware.bin Binary files differindex c5169563..13a7604e 100644 --- a/EdgeRelease/DuetMaestroFirmware.bin +++ b/EdgeRelease/DuetMaestroFirmware.bin diff --git a/src/BugList.txt b/src/BugList.txt index fdcfa1d3..2e6a5753 100644 --- a/src/BugList.txt +++ b/src/BugList.txt @@ -123,6 +123,24 @@ Remaining: - [no fault] Report workspace coordinates to 2dp not 1dp to DWC (https://www.duet3d.com/forum/thread.php?pid=43789#p43789) - [done in 2.0] G0 not to use G1 F parameter, move at machine limits instead (CNC, https://www.duet3d.com/forum/thread.php?pid=43825#p43825) +- [fixed in 2.0b2, test] BUG M667 S1 echoes the new kinematics +- [fixed in 2.0b2] BUG DWC disconnects with JSON error after uploading a GCode file to Ormerod/Maestro +- [done in 2.0b2] Support F parameter in G0 command again when machine mode is FFF +- [fixed in 2.0b2, test] BUG: G0 command after G1 E command does extrusion +- [believed fixed in 2.0b2] BUG movement system hangs sometimes if using very high microstepping, e.g. janke PSU model and config.g + +- BUG manual probing, see https://github.com/dc42/RepRapFirmware/issues/170#issuecomment-380790290 +- BUG SCARA continuous rotation doesn't work +- BUG sounds like SCARA only checks that the end point is within limits, but for a G1 move intermediate positions may violate the minimum radius + +- When >1 hot end heater, add T0/T1 prefix to M105 response for compatibiity with Marlin etc. +- Laser support, see https://forum.duet3d.com/topic/4702/laser-cnc-support-in-rrf-gcode-semantics/4 +- support M205 for setting jerk +- support G12 clean tool? +- support estimated print time comment from slic3r PE +- Danny's modified SCARA kinematics (workpiece is on a plate, extruder is fixed) +- Look at Bezier speed curves or other S-curve acceleration, https://github.com/MarlinFirmware/Marlin/pull/10373/files +- after homing, warn if outside M208 movement limits on SCARA, polar etc. - Unexpected heaters off/tool selection behaviour, https://www.duet3d.com/forum/thread.php?pid=43059#p43059 - warn when using : where ; was probably meant - Error message if you attempt movement with VIN < minimum @@ -142,6 +160,7 @@ Remaining: - Should bltouch use digital probe mode? Some users having problems with P25 in G31 command. - M584 when assigning a drive, unmap any existing assignment. Also allow an axis to be mapped to driver -1. - Add S4 option to G1 command, like S1 but no endstop checks (needed for CoreXY, CoreXZ) +- When uploading while a file is being printed, don't allow the currently-printing file to be replaced - if a homing command in an SD print file is aborted due to e.g. G1 Z5 in the homing file, error message should be written to both DWC and PanelDue - [no fault] stall detect on Z axis @@ -151,7 +170,7 @@ Remaining: - [hopefully this is fixed by the DHCP fixes] https://www.duet3d.com/forum/thread.php?pid=37797#p37797 (Duet Ethernet long delays between moves) - [no idea, bus fault in pbuf_cat] Look at https://www.duet3d.com/forum/thread.php?pid=37551#p37551 -- When Z probe readings are out of tolerance, display the lowest difference seen between consecutive readings +- When Z probe readings are out of tolerance, display the lowest difference seen between consecutive readings? - laser control, https://www.duet3d.com/forum/thread.php?pid=37891#p37891 - slow DWC but fast FTP, https://www.duet3d.com/forum/thread.php?pid=38345#p38345 diff --git a/src/Configuration.h b/src/Configuration.h index 2b25f138..f2812f3f 100644 --- a/src/Configuration.h +++ b/src/Configuration.h @@ -191,23 +191,23 @@ constexpr size_t MaxFilenameLength = 100; constexpr size_t MaxHeaterNameLength = 20; // Maximum number of characters in a heater name -// Output buffer lengths +// Output buffer length and number of buffers +// When using RTOS, it must be possible to fit an HTTP response header in a single buffer. Our headers are currently about 230 bytes long. #if SAM4E || SAM4S || SAME70 -constexpr uint16_t OUTPUT_BUFFER_SIZE = 128; // How many bytes does each OutputBuffer hold? -constexpr size_t OUTPUT_BUFFER_COUNT = 40; // How many OutputBuffer instances do we have? -constexpr size_t RESERVED_OUTPUT_BUFFERS = 3; // Number of reserved output buffers after long responses. Must be enough for an HTTP header. - // DC 2018-04-12 increased this from 2 to 3 because we were running out of buffers - // when a file upload completes and there are a lot of files +constexpr size_t OUTPUT_BUFFER_SIZE = 256; // How many bytes does each OutputBuffer hold? +constexpr size_t OUTPUT_BUFFER_COUNT = 20; // How many OutputBuffer instances do we have? +constexpr size_t RESERVED_OUTPUT_BUFFERS = 2; // Number of reserved output buffers after long responses #elif SAM3XA -constexpr uint16_t OUTPUT_BUFFER_SIZE = 128; // How many bytes does each OutputBuffer hold? -constexpr size_t OUTPUT_BUFFER_COUNT = 32; // How many OutputBuffer instances do we have? -constexpr size_t RESERVED_OUTPUT_BUFFERS = 3; // Number of reserved output buffers after long responses. Must be enough for an HTTP header +constexpr size_t OUTPUT_BUFFER_SIZE = 256; // How many bytes does each OutputBuffer hold? +constexpr size_t OUTPUT_BUFFER_COUNT = 16; // How many OutputBuffer instances do we have? +constexpr size_t RESERVED_OUTPUT_BUFFERS = 2; // Number of reserved output buffers after long responses #else # error #endif // Move system -constexpr float DefaultFeedrate = 3000.0; // The initial requested feed rate after resetting the printer, in mm/min +constexpr float DefaultFeedRate = 3000.0; // The initial requested feed rate after resetting the printer, in mm/min +constexpr float DefaultG0FeedRate = 18000; // The initial feed rate for G0 commands 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) diff --git a/src/GCodes/GCodeBuffer.cpp b/src/GCodes/GCodeBuffer.cpp index afdcae81..e3222344 100644 --- a/src/GCodes/GCodeBuffer.cpp +++ b/src/GCodes/GCodeBuffer.cpp @@ -917,7 +917,7 @@ bool GCodeBuffer::PushState() GCodeMachineState * const ms = GCodeMachineState::Allocate(); ms->previous = machineState; - ms->feedrate = machineState->feedrate; + ms->feedRate = machineState->feedRate; ms->fileState.CopyFrom(machineState->fileState); ms->lockedResources = machineState->lockedResources; ms->drivesRelative = machineState->drivesRelative; diff --git a/src/GCodes/GCodeMachineState.cpp b/src/GCodes/GCodeMachineState.cpp index abe6d388..046cd872 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), errorMessage(nullptr), state(GCodeState::normal), + : previous(nullptr), feedRate(DefaultFeedRate * SecondsToMinutes), fileState(), lockedResources(0), errorMessage(nullptr), state(GCodeState::normal), drivesRelative(false), axesRelative(false), doingFileMacro(false), runningM501(false), runningM502(false), volumetricExtrusion(false), useMachineCoordinates(false), useMachineCoordinatesSticky(false), waitingForAcknowledgement(false), messageAcknowledged(false) { diff --git a/src/GCodes/GCodeMachineState.h b/src/GCodes/GCodeMachineState.h index 2f2f1d97..eab82260 100644 --- a/src/GCodes/GCodeMachineState.h +++ b/src/GCodes/GCodeMachineState.h @@ -89,7 +89,7 @@ public: GCodeMachineState(); GCodeMachineState *previous; - float feedrate; + float feedRate; FileData fileState; ResourceBitmap lockedResources; const char *errorMessage; @@ -119,7 +119,7 @@ public: { drivesRelative = other.drivesRelative; axesRelative = other.axesRelative; - feedrate = other.feedrate; + feedRate = other.feedRate; } static void Release(GCodeMachineState *ms); diff --git a/src/GCodes/GCodes.cpp b/src/GCodes/GCodes.cpp index 73d2af62..9f3917ae 100644 --- a/src/GCodes/GCodes.cpp +++ b/src/GCodes/GCodes.cpp @@ -42,6 +42,19 @@ const size_t gcodeReplyLength = 2048; // long enough to pass back a reasonable number of files in response to M20 +// Set up some default values for special moves, e.g. for Z probing and firmware retraction +void GCodes::RawMove::SetDefaults() +{ + moveType = 0; + isCoordinated = false; + usingStandardFeedrate = false; + usePressureAdvance = false; + endStopsToCheck = 0; + filePos = noFilePosition; + xAxes = DefaultXAxisMapping; + yAxes = DefaultYAxisMapping; +} + GCodes::GCodes(Platform& p) : platform(p), machineType(MachineType::fff), active(false), #if HAS_VOLTAGE_MONITOR @@ -489,7 +502,7 @@ void GCodes::RunStateMachine(GCodeBuffer& gb, const StringRef& reply) doingToolChange = true; SaveFanSpeeds(); memcpy(toolChangeRestorePoint.moveCoords, currentUserPosition, MaxAxes * sizeof(currentUserPosition[0])); - toolChangeRestorePoint.feedRate = gb.MachineState().feedrate; + toolChangeRestorePoint.feedRate = gb.MachineState().feedRate; gb.AdvanceState(); if ((gb.MachineState().toolChangeParam & TFreeBit) != 0) { @@ -548,7 +561,7 @@ void GCodes::RunStateMachine(GCodeBuffer& gb, const StringRef& reply) { // Restore the original Z axis user position, so that different tool Z offsets work even if the first move after the tool change doesn't have a Z coordinate currentUserPosition[Z_AXIS] = toolChangeRestorePoint.moveCoords[Z_AXIS]; - gb.MachineState().feedrate = toolChangeRestorePoint.feedRate; + gb.MachineState().feedRate = toolChangeRestorePoint.feedRate; // We don't restore the default fan speed in case the user wants to use a different one for the new tool doingToolChange = false; @@ -613,12 +626,8 @@ void GCodes::RunStateMachine(GCodeBuffer& gb, const StringRef& reply) { moveBuffer.coords[drive] = 0.0; } - moveBuffer.feedRate = DefaultFeedrate * SecondsToMinutes; // ask for a good feed rate, we may have paused during a slow move - moveBuffer.moveType = 0; - moveBuffer.isCoordinated = false; - moveBuffer.endStopsToCheck = 0; - moveBuffer.usePressureAdvance = false; - moveBuffer.filePos = noFilePosition; + moveBuffer.SetDefaults(); + moveBuffer.feedRate = DefaultFeedRate * SecondsToMinutes; // ask for a good feed rate, we may have paused during a slow move if (gb.GetState() == GCodeState::resuming1 && currentZ > pauseRestorePoint.moveCoords[Z_AXIS]) { // First move the head to the correct XY point, then move it down in a separate move @@ -643,7 +652,7 @@ void GCodes::RunStateMachine(GCodeBuffer& gb, const StringRef& reply) } virtualExtruderPosition = pauseRestorePoint.virtualExtruderPosition; // reset the extruder position in case we are receiving absolute extruder moves moveBuffer.virtualExtruderPosition = pauseRestorePoint.virtualExtruderPosition; - fileGCode->MachineState().feedrate = pauseRestorePoint.feedRate; + fileGCode->MachineState().feedRate = pauseRestorePoint.feedRate; moveFractionToSkip = pauseRestorePoint.proportionDone; isPaused = false; reply.copy("Printing resumed"); @@ -728,17 +737,11 @@ void GCodes::RunStateMachine(GCodeBuffer& gb, const StringRef& reply) { if (move.IsAccessibleProbePoint(x, y)) { - moveBuffer.moveType = 0; - moveBuffer.isCoordinated = false; - moveBuffer.endStopsToCheck = 0; - moveBuffer.usePressureAdvance = false; - moveBuffer.filePos = noFilePosition; + moveBuffer.SetDefaults(); moveBuffer.coords[X_AXIS] = x - platform.GetCurrentZProbeParameters().xOffset; moveBuffer.coords[Y_AXIS] = y - platform.GetCurrentZProbeParameters().yOffset; moveBuffer.coords[Z_AXIS] = platform.GetZProbeStartingHeight(); moveBuffer.feedRate = platform.GetZProbeTravelSpeed(); - moveBuffer.xAxes = DefaultXAxisMapping; - moveBuffer.yAxes = DefaultYAxisMapping; NewMoveAvailable(1); tapsDone = 0; @@ -811,15 +814,10 @@ void GCodes::RunStateMachine(GCodeBuffer& gb, const StringRef& reply) { zProbeTriggered = false; platform.SetProbing(true); - moveBuffer.moveType = 0; - moveBuffer.isCoordinated = false; + moveBuffer.SetDefaults(); moveBuffer.endStopsToCheck = ZProbeActive; - moveBuffer.usePressureAdvance = false; - moveBuffer.filePos = noFilePosition; moveBuffer.coords[Z_AXIS] = -platform.GetZProbeDiveHeight(); moveBuffer.feedRate = platform.GetCurrentZProbeParameters().probeSpeed; - moveBuffer.xAxes = DefaultXAxisMapping; - moveBuffer.yAxes = DefaultYAxisMapping; NewMoveAvailable(1); gb.AdvanceState(); } @@ -856,15 +854,9 @@ void GCodes::RunStateMachine(GCodeBuffer& gb, const StringRef& reply) } // Move back up to the dive height - moveBuffer.moveType = 0; - moveBuffer.isCoordinated = false; - moveBuffer.endStopsToCheck = 0; - moveBuffer.usePressureAdvance = false; - moveBuffer.filePos = noFilePosition; + moveBuffer.SetDefaults(); moveBuffer.coords[Z_AXIS] = platform.GetZProbeStartingHeight(); moveBuffer.feedRate = platform.GetZProbeTravelSpeed(); - moveBuffer.xAxes = DefaultXAxisMapping; - moveBuffer.yAxes = DefaultYAxisMapping; NewMoveAvailable(1); gb.AdvanceState(); @@ -976,15 +968,9 @@ void GCodes::RunStateMachine(GCodeBuffer& gb, const StringRef& reply) // States used for G30 probing case GCodeState::probingAtPoint0: // Initial state when executing G30 with a P parameter. Start by moving to the dive height at the current position. - moveBuffer.moveType = 0; - moveBuffer.isCoordinated = false; - moveBuffer.endStopsToCheck = 0; - moveBuffer.usePressureAdvance = false; - moveBuffer.filePos = noFilePosition; + moveBuffer.SetDefaults(); moveBuffer.coords[Z_AXIS] = platform.GetZProbeStartingHeight(); moveBuffer.feedRate = platform.GetZProbeTravelSpeed(); - moveBuffer.xAxes = DefaultXAxisMapping; - moveBuffer.yAxes = DefaultYAxisMapping; NewMoveAvailable(1); gb.AdvanceState(); break; @@ -995,16 +981,10 @@ void GCodes::RunStateMachine(GCodeBuffer& gb, const StringRef& reply) { // Head is at the dive height but needs to be moved to the correct XY position. // The XY coordinates have already been stored. - moveBuffer.moveType = 0; - moveBuffer.isCoordinated = false; - moveBuffer.endStopsToCheck = 0; - moveBuffer.usePressureAdvance = false; - moveBuffer.filePos = noFilePosition; + moveBuffer.SetDefaults(); (void)reprap.GetMove().GetProbeCoordinates(g30ProbePointIndex, moveBuffer.coords[X_AXIS], moveBuffer.coords[Y_AXIS], true); moveBuffer.coords[Z_AXIS] = platform.GetZProbeStartingHeight(); moveBuffer.feedRate = platform.GetZProbeTravelSpeed(); - moveBuffer.xAxes = DefaultXAxisMapping; - moveBuffer.yAxes = DefaultYAxisMapping; NewMoveAvailable(1); InitialiseTaps(); @@ -1071,17 +1051,12 @@ void GCodes::RunStateMachine(GCodeBuffer& gb, const StringRef& reply) { zProbeTriggered = false; platform.SetProbing(true); - moveBuffer.moveType = 0; - moveBuffer.isCoordinated = false; + moveBuffer.SetDefaults(); moveBuffer.endStopsToCheck = ZProbeActive; - moveBuffer.usePressureAdvance = false; - moveBuffer.filePos = noFilePosition; moveBuffer.coords[Z_AXIS] = (GetAxisIsHomed(Z_AXIS)) ? -platform.GetZProbeDiveHeight() // Z axis has been homed, so no point in going very far : -1.1 * platform.AxisTotalLength(Z_AXIS); // Z axis not homed yet, so treat this as a homing move moveBuffer.feedRate = platform.GetCurrentZProbeParameters().probeSpeed; - moveBuffer.xAxes = DefaultXAxisMapping; - moveBuffer.yAxes = DefaultYAxisMapping; NewMoveAvailable(1); gb.AdvanceState(); } @@ -1151,15 +1126,9 @@ void GCodes::RunStateMachine(GCodeBuffer& gb, const StringRef& reply) } // Move back up to the dive height before we change anything, in particular before we adjust leadscrews - moveBuffer.moveType = 0; - moveBuffer.isCoordinated = false; - moveBuffer.endStopsToCheck = 0; - moveBuffer.usePressureAdvance = false; - moveBuffer.filePos = noFilePosition; + moveBuffer.SetDefaults(); moveBuffer.coords[Z_AXIS] = platform.GetZProbeStartingHeight(); moveBuffer.feedRate = platform.GetZProbeTravelSpeed(); - moveBuffer.xAxes = DefaultXAxisMapping; - moveBuffer.yAxes = DefaultYAxisMapping; NewMoveAvailable(1); gb.AdvanceState(); @@ -1278,21 +1247,16 @@ void GCodes::RunStateMachine(GCodeBuffer& gb, const StringRef& reply) const AxesBitmap xAxes = reprap.GetCurrentXAxes(); const AxesBitmap yAxes = reprap.GetCurrentYAxes(); reprap.GetMove().GetCurrentUserPosition(moveBuffer.coords, 0, xAxes, yAxes); + moveBuffer.coords[Z_AXIS] += retractHop; for (size_t i = numTotalAxes; i < DRIVES; ++i) { moveBuffer.coords[i] = 0.0; } + moveBuffer.SetDefaults(); moveBuffer.feedRate = platform.MaxFeedrate(Z_AXIS); - moveBuffer.coords[Z_AXIS] += retractHop; - currentZHop = retractHop; - moveBuffer.moveType = 0; - moveBuffer.isCoordinated = false; - moveBuffer.isFirmwareRetraction = true; - moveBuffer.usePressureAdvance = false; moveBuffer.filePos = (&gb == fileGCode) ? gb.GetFilePosition(fileInput->BytesCached()) : noFilePosition; moveBuffer.canPauseAfter = false; // don't pause after a retraction because that could cause too much retraction - moveBuffer.xAxes = xAxes; - moveBuffer.yAxes = yAxes; + currentZHop = retractHop; NewMoveAvailable(1); gb.SetState(GCodeState::normal); } @@ -1316,15 +1280,11 @@ void GCodes::RunStateMachine(GCodeBuffer& gb, const StringRef& reply) { moveBuffer.coords[numTotalAxes + tool->Drive(i)] = retractLength + retractExtra; } + moveBuffer.SetDefaults(); moveBuffer.feedRate = unRetractSpeed; - moveBuffer.moveType = 0; - moveBuffer.isCoordinated = false; moveBuffer.isFirmwareRetraction = true; - moveBuffer.usePressureAdvance = false; moveBuffer.filePos = (&gb == fileGCode) ? gb.MachineState().fileState.GetPosition() - fileInput->BytesCached() : noFilePosition; moveBuffer.canPauseAfter = true; - moveBuffer.xAxes = xAxes; - moveBuffer.yAxes = yAxes; NewMoveAvailable(1); } gb.SetState(GCodeState::normal); @@ -1628,6 +1588,7 @@ void GCodes::DoPause(GCodeBuffer& gb, PauseReason reason, const char *msg) else { // Pausing a file print via another input source or for some other reason + pauseRestorePoint.feedRate = fileGCode->MachineState().feedRate; // set up the default const bool movesSkipped = reprap.GetMove().PausePrint(pauseRestorePoint); // tell Move we wish to pause the current print if (movesSkipped) @@ -1648,10 +1609,10 @@ void GCodes::DoPause(GCodeBuffer& gb, PauseReason reason, const char *msg) else { // We were not able to skip any moves, and if there is a move waiting then we can't skip that one either - pauseRestorePoint.feedRate = fileGCode->MachineState().feedrate; + pauseRestorePoint.feedRate = fileGCode->MachineState().feedRate; pauseRestorePoint.virtualExtruderPosition = virtualExtruderPosition; - // TODO: when we use RTOS there is a possible race condition in the following, + // TODO: when using RTOS there is a possible race condition in the following, // because we might try to pause when a waiting move has just been added but before the gcode buffer has been re-initialised ready for the next command pauseRestorePoint.filePos = fileGCode->GetFilePosition(fileInput->BytesCached()); #if SUPPORT_IOBITS @@ -1788,7 +1749,7 @@ bool GCodes::DoEmergencyPause() else { // We were not able to skip any moves, and if there is a move waiting then we can't skip that one either - pauseRestorePoint.feedRate = fileGCode->MachineState().feedrate; + pauseRestorePoint.feedRate = fileGCode->MachineState().feedRate; pauseRestorePoint.virtualExtruderPosition = virtualExtruderPosition; // TODO: when we use RTOS there is a possible race condition in the following, @@ -2106,10 +2067,29 @@ void GCodes::Pop(GCodeBuffer& gb) } // Set up the extrusion and feed rate of a move for the Move class -// 'moveType' is the S parameter in the G0 or G1 command, or zero for a G2 or G3 command +// 'moveBuffer.moveType' and 'moveBuffer.isCoordinated' must be set up before calling this // Returns true if this gcode is valid so far, false if it should be discarded -bool GCodes::LoadExtrusionFromGCode(GCodeBuffer& gb) +bool GCodes::LoadExtrusionAndFeedrateFromGCode(GCodeBuffer& gb) { + // Deal with feed rate + if (moveBuffer.isCoordinated || machineType == MachineType::fff) + { + if (gb.Seen(feedrateLetter)) + { + const float rate = gb.GetFValue() * distanceScale; + gb.MachineState().feedRate = (moveBuffer.moveType == 0) + ? rate * speedFactor + : rate * SecondsToMinutes; // don't apply the speed factor to homing and other special moves + } + moveBuffer.feedRate = gb.MachineState().feedRate; + moveBuffer.usingStandardFeedrate = true; + } + else + { + moveBuffer.feedRate = DefaultG0FeedRate; // use maximum feed rate, the M203 parameters will limit it + moveBuffer.usingStandardFeedrate = false; + } + // Zero every extruder drive as some drives may not be moved for (size_t drive = numTotalAxes; drive < DRIVES; drive++) { @@ -2117,11 +2097,11 @@ bool GCodes::LoadExtrusionFromGCode(GCodeBuffer& gb) } moveBuffer.hasExtrusion = false; - // If we are extruding, check that we have a tool to extrude with - if (gb.Seen(extrudeLetter)) + // Check if we are extruding + if (moveBuffer.isCoordinated && gb.Seen(extrudeLetter)) { - moveBuffer.hasExtrusion = true; + // Check that we have a tool to extrude with Tool* const tool = reprap.GetCurrentTool(); if (tool == nullptr) { @@ -2129,6 +2109,7 @@ bool GCodes::LoadExtrusionFromGCode(GCodeBuffer& gb) return false; } + moveBuffer.hasExtrusion = true; const size_t eMoveCount = tool->DriveCount(); if (eMoveCount != 0) { @@ -2217,20 +2198,6 @@ bool GCodes::LoadExtrusionFromGCode(GCodeBuffer& gb) return true; } -// Set up the feed rate of a move -// 'moveType' is the S parameter in the G1 command, or zero for a G2 or G3 command -void GCodes::LoadFeedrateFromGCode(GCodeBuffer& gb) -{ - if (moveBuffer.moveType >= 0 && gb.Seen(feedrateLetter)) - { - const float rate = gb.GetFValue() * distanceScale; - gb.MachineState().feedrate = (moveBuffer.moveType == 0) - ? rate * speedFactor - : rate * SecondsToMinutes; // don't apply the speed factor to homing and other special moves - } - moveBuffer.feedRate = gb.MachineState().feedrate; -} - // Check that enough axes have been homed, returning true if insufficient axes homed bool GCodes::CheckEnoughAxesHomed(AxesBitmap axesMoved) { @@ -2381,16 +2348,7 @@ const char* GCodes::DoStraightMove(GCodeBuffer& gb, bool isCoordinated) } } - // Deal with extrusion and feed rate - if (isCoordinated) - { - LoadExtrusionFromGCode(gb); - LoadFeedrateFromGCode(gb); - } - else - { - moveBuffer.feedRate = platform.GetMaxTravelAcceleration(); - } + LoadExtrusionAndFeedrateFromGCode(gb); // Set up the move. We must assign segmentsLeft last, so that when Move runs as a separate task the move won't be picked up by the Move process before it is complete. // Note that if this is an extruder-only move, we don't do axis movements to allow for tool offset changes, we defer those until an axis moves. @@ -2594,8 +2552,7 @@ const char* GCodes::DoArcMove(GCodeBuffer& gb, bool clockwise) } } - LoadExtrusionFromGCode(gb); - LoadFeedrateFromGCode(gb); + LoadExtrusionAndFeedrateFromGCode(gb); moveBuffer.usePressureAdvance = moveBuffer.hasExtrusion; @@ -4043,10 +4000,8 @@ GCodeResult GCodes::RetractFilament(GCodeBuffer& gb, bool retract) { moveBuffer.coords[i] = 0.0; } - moveBuffer.moveType = 0; - moveBuffer.isCoordinated = false; + moveBuffer.SetDefaults(); moveBuffer.isFirmwareRetraction = true; - moveBuffer.usePressureAdvance = false; moveBuffer.filePos = (&gb == fileGCode) ? gb.GetFilePosition(fileInput->BytesCached()) : noFilePosition; moveBuffer.xAxes = xAxes; moveBuffer.yAxes = yAxes; @@ -4340,7 +4295,7 @@ void GCodes::SavePosition(RestorePoint& rp, const GCodeBuffer& gb) const rp.moveCoords[axis] = currentUserPosition[axis]; } - rp.feedRate = gb.MachineState().feedrate; + rp.feedRate = gb.MachineState().feedRate; rp.virtualExtruderPosition = virtualExtruderPosition; #if SUPPORT_IOBITS @@ -4357,7 +4312,7 @@ void GCodes::RestorePosition(const RestorePoint& rp, GCodeBuffer *gb) } if (gb != nullptr) { - gb->MachineState().feedrate = rp.feedRate; + gb->MachineState().feedRate = rp.feedRate; } #if SUPPORT_IOBITS @@ -4726,6 +4681,10 @@ OutputBuffer *GCodes::GenerateJsonStatusResponse(int type, int seq, ResponseSour { statusResponse->cat('\n'); } + if (statusResponse->HadOverflow()) + { + OutputBuffer::ReleaseAll(statusResponse); + } return statusResponse; } diff --git a/src/GCodes/GCodes.h b/src/GCodes/GCodes.h index dd516481..a952b92a 100644 --- a/src/GCodes/GCodes.h +++ b/src/GCodes/GCodes.h @@ -129,6 +129,9 @@ public: uint8_t canPauseAfter : 1; // true if we can pause just after this move and successfully restart uint8_t hasExtrusion : 1; // true if the move includes extrusion - only valid if the move was set up by SetupMove uint8_t isCoordinated : 1; // true if this is a coordinates move + uint8_t usingStandardFeedrate : 1; // true if this move uses the standard feed rate + + void SetDefaults(); // set up default values }; GCodes(Platform& p); @@ -202,6 +205,7 @@ public: #endif const char *GetAxisLetters() const { return axisLetters; } // Return a null-terminated string of axis letters indexed by drive + MachineType GetMachineType() const { return machineType; } #if SUPPORT_12864_LCD bool ProcessCommandFromLcd(const char *cmd); // Process a GCode command from the 12864 LCD returning true if the command was accepted @@ -269,8 +273,7 @@ private: GCodeResult SetDateTime(GCodeBuffer& gb,const StringRef& reply); // Deal with a M905 GCodeResult SavePosition(GCodeBuffer& gb,const StringRef& reply); // Deal with G60 - bool LoadExtrusionFromGCode(GCodeBuffer& gb); // Set up the extrusion of a move - void LoadFeedrateFromGCode(GCodeBuffer& gb); // Set up the feed rate of a move + bool LoadExtrusionAndFeedrateFromGCode(GCodeBuffer& gb); // Set up the extrusion of a move bool Push(GCodeBuffer& gb); // Push feedrate etc on the stack void Pop(GCodeBuffer& gb); // Pop feedrate etc diff --git a/src/GCodes/GCodes2.cpp b/src/GCodes/GCodes2.cpp index 01a694a8..7fe9747b 100644 --- a/src/GCodes/GCodes2.cpp +++ b/src/GCodes/GCodes2.cpp @@ -754,7 +754,7 @@ bool GCodes::HandleMcode(GCodeBuffer& gb, const StringRef& reply) // We executed M23 to set the file offset, which normally means that we are executing resurrect.g. // We need to copy the absolute/relative and volumetric extrusion flags over fileGCode->OriginalMachineState().drivesRelative = gb.MachineState().drivesRelative; - fileGCode->OriginalMachineState().feedrate = gb.MachineState().feedrate; + fileGCode->OriginalMachineState().feedRate = gb.MachineState().feedRate; fileGCode->OriginalMachineState().volumetricExtrusion = gb.MachineState().volumetricExtrusion; fileToPrint.Seek(fileOffsetToPrint); moveFractionToSkip = moveFractionToStartAt; @@ -1999,7 +1999,7 @@ bool GCodes::HandleMcode(GCodeBuffer& gb, const StringRef& reply) GCodeMachineState *ms = &gcodeSources[i]->MachineState(); while (ms != nullptr) { - ms->feedrate *= speedFactorRatio; + ms->feedRate *= speedFactorRatio; ms = ms->previous; } } @@ -2517,6 +2517,7 @@ bool GCodes::HandleMcode(GCodeBuffer& gb, const StringRef& reply) HandleReply(gb, false, statusResponse); return true; } + result = GCodeResult::notFinished; // we ran out of buffers, so try again later } break; @@ -4261,7 +4262,7 @@ bool GCodes::HandleResult(GCodeBuffer& gb, GCodeResult rslt, const StringRef& re { String<ScratchStringLength> scratchString; gb.PrintCommand(scratchString.GetRef()); - scratchString.cat(": "); + reply.Prepend(": "); reply.Prepend(scratchString.c_str()); } break; diff --git a/src/GCodes/GCodes3.cpp b/src/GCodes/GCodes3.cpp index 3d300246..ff3c6f1b 100644 --- a/src/GCodes/GCodes3.cpp +++ b/src/GCodes/GCodes3.cpp @@ -352,7 +352,7 @@ GCodeResult GCodes::SimulateFile(GCodeBuffer& gb, const StringRef &reply, const axesHomedBeforeSimulation = axesHomed; axesHomed = LowestNBits<AxesBitmap>(numVisibleAxes); // pretend all axes are homed reprap.GetMove().GetCurrentUserPosition(simulationRestorePoint.moveCoords, 0, reprap.GetCurrentXAxes(), reprap.GetCurrentYAxes()); - simulationRestorePoint.feedRate = gb.MachineState().feedrate; + simulationRestorePoint.feedRate = gb.MachineState().feedRate; } simulationTime = 0.0; exitSimulationWhenFileComplete = true; @@ -389,7 +389,7 @@ GCodeResult GCodes::ChangeSimulationMode(GCodeBuffer& gb, const StringRef &reply axesHomedBeforeSimulation = axesHomed; axesHomed = LowestNBits<AxesBitmap>(numVisibleAxes); // pretend all axes are homed reprap.GetMove().GetCurrentUserPosition(simulationRestorePoint.moveCoords, 0, reprap.GetCurrentXAxes(), reprap.GetCurrentYAxes()); - simulationRestorePoint.feedRate = gb.MachineState().feedrate; + simulationRestorePoint.feedRate = gb.MachineState().feedRate; } simulationTime = 0.0; } @@ -781,9 +781,9 @@ GCodeResult GCodes::ProbeTool(GCodeBuffer& gb, const StringRef& reply) if (gb.Seen(feedrateLetter)) { const float rate = gb.GetFValue() * distanceScale; - gb.MachineState().feedrate = rate * SecondsToMinutes; // don't apply the speed factor to homing and other special moves + gb.MachineState().feedRate = rate * SecondsToMinutes; // don't apply the speed factor to homing and other special moves } - moveBuffer.feedRate = gb.MachineState().feedrate; + moveBuffer.feedRate = gb.MachineState().feedRate; // Kick off new movement NewMoveAvailable(1); diff --git a/src/GCodes/RestorePoint.cpp b/src/GCodes/RestorePoint.cpp index b75fe8a4..51eb5f16 100644 --- a/src/GCodes/RestorePoint.cpp +++ b/src/GCodes/RestorePoint.cpp @@ -19,7 +19,7 @@ void RestorePoint::Init() moveCoords[i] = 0.0; } - feedRate = DefaultFeedrate * SecondsToMinutes; + feedRate = DefaultFeedRate * SecondsToMinutes; virtualExtruderPosition = 0.0; filePos = noFilePosition; proportionDone = 0.0; diff --git a/src/Libraries/General/SafeVsnprintf.cpp b/src/Libraries/General/SafeVsnprintf.cpp index fb153f88..0952c243 100644 --- a/src/Libraries/General/SafeVsnprintf.cpp +++ b/src/Libraries/General/SafeVsnprintf.cpp @@ -30,6 +30,8 @@ #include <climits> #include <cmath> +#include "Strnlen.h" + // The following should be enough for 32-bit int/long and 64-bit long long constexpr size_t MaxLongDigits = 10; // to print 4294967296 constexpr size_t MaxUllDigits = 20; // to print 18446744073709551616 @@ -103,12 +105,8 @@ static bool prints(SStringBuf& apBuf, const char *apString ) if (apBuf.flags.printLimit > 0 && apBuf.flags.isString) { // It's a string so printLimit is the max number of characters to print from the string. - // Don't call strlen on it because it might not be null terminated. - count = 0; - for (const char *s = apString; count < apBuf.flags.printLimit && *s != 0; ++s) - { - ++count; - } + // Don't call strlen on it because it might not be null terminated, use Strnlen instead. + count = (int)Strnlen(apString, apBuf.flags.printLimit); } else { diff --git a/src/Libraries/General/SafeVsnprintf.h b/src/Libraries/General/SafeVsnprintf.h index 4a8db786..9a2aa719 100644 --- a/src/Libraries/General/SafeVsnprintf.h +++ b/src/Libraries/General/SafeVsnprintf.h @@ -12,7 +12,7 @@ #include <cstddef> int SafeVsnprintf(char *buffer, size_t maxLen, const char *format, va_list args); -int SafeSnprintf(char* buffer, size_t maxLen, const char* format, ...); +int SafeSnprintf(char* buffer, size_t maxLen, const char* format, ...) __attribute__ ((format (printf, 3, 4))); #define vsnprintf(b, m, f, a) static_assert(false, "Do not use vsnprintf, use SafeVsnprintf instead") #define snprintf(b, m, f, ...) static_assert(false, "Do not use snprintf, use SafeSnprintf instead") diff --git a/src/Libraries/General/StringRef.cpp b/src/Libraries/General/StringRef.cpp index a65306fb..45350737 100644 --- a/src/Libraries/General/StringRef.cpp +++ b/src/Libraries/General/StringRef.cpp @@ -15,23 +15,12 @@ # include "RTOSIface.h" #endif -// Need to define strnlen here because it isn't ISO standard -size_t strnlen(const char *s, size_t n) -{ - size_t rslt = 0; - while (rslt < n && s[rslt] != 0) - { - ++rslt; - } - return rslt; -} - //************************************************************************************************* // StringRef class member implementations size_t StringRef::strlen() const { - return strnlen(p, len - 1); + return Strnlen(p, len - 1); } int StringRef::printf(const char *fmt, ...) const diff --git a/src/Libraries/General/StringRef.h b/src/Libraries/General/StringRef.h index 6c74fd71..c0735522 100644 --- a/src/Libraries/General/StringRef.h +++ b/src/Libraries/General/StringRef.h @@ -12,8 +12,7 @@ #include <cstdarg> // for va_args #include <cstring> // for strlen -// Need to declare strnlen here because it isn't ISO standard -size_t strnlen(const char *s, size_t n); +#include "Strnlen.h" // Class to describe a string buffer, including its length. This saves passing buffer lengths around everywhere. class StringRef @@ -54,7 +53,7 @@ public: StringRef GetRef() { return StringRef(storage, Len + 1); } const char *c_str() const { return storage; } - size_t strlen() const { return strnlen(storage, Len); } + size_t strlen() const { return Strnlen(storage, Len); } bool IsEmpty() const { return storage[0] == 0; } // char *Pointer() { return storage; } char& operator[](size_t index) { return storage[index]; } diff --git a/src/Libraries/General/Strnlen.cpp b/src/Libraries/General/Strnlen.cpp new file mode 100644 index 00000000..d797ee33 --- /dev/null +++ b/src/Libraries/General/Strnlen.cpp @@ -0,0 +1,21 @@ +/* + * Strnlen.cpp + * + * Created on: 17 Apr 2018 + * Author: David + */ + +#include "Strnlen.h" + +// Need to define strnlen here because it isn't ISO standard +size_t Strnlen(const char *s, size_t n) +{ + size_t rslt = 0; + while (rslt < n && s[rslt] != 0) + { + ++rslt; + } + return rslt; +} + +// End diff --git a/src/Libraries/General/Strnlen.h b/src/Libraries/General/Strnlen.h new file mode 100644 index 00000000..d4bc40d6 --- /dev/null +++ b/src/Libraries/General/Strnlen.h @@ -0,0 +1,16 @@ +/* + * Strnlen.h + * + * Created on: 17 Apr 2018 + * Author: David + */ + +#ifndef SRC_LIBRARIES_GENERAL_STRNLEN_H_ +#define SRC_LIBRARIES_GENERAL_STRNLEN_H_ + +#include <cstddef> + +// 'strnlen' isn't ISO standard, so we define our own +size_t Strnlen(const char *s, size_t n); + +#endif /* SRC_LIBRARIES_GENERAL_STRNLEN_H_ */ diff --git a/src/Movement/DDA.cpp b/src/Movement/DDA.cpp index 45250ae9..a8cc3515 100644 --- a/src/Movement/DDA.cpp +++ b/src/Movement/DDA.cpp @@ -383,6 +383,7 @@ bool DDA::Init(GCodes::RawMove &nextMove, bool doMotorMapping) endStopsToCheck = nextMove.endStopsToCheck; canPauseBefore = nextMove.canPauseBefore; canPauseAfter = nextMove.canPauseAfter; + usingStandardFeedrate = nextMove.usingStandardFeedrate; filePos = nextMove.filePos; isPrintingMove = xyMoving && extruding; usePressureAdvance = nextMove.usePressureAdvance; @@ -538,6 +539,7 @@ bool DDA::Init(const float_t adjustments[DRIVES]) endStopsToCheck = 0; canPauseBefore = true; canPauseAfter = true; + usingStandardFeedrate = false; usePressureAdvance = false; virtualExtruderPosition = prev->virtualExtruderPosition; hadLookaheadUnderrun = false; diff --git a/src/Movement/DDA.h b/src/Movement/DDA.h index e1c2e2f5..5c340c8a 100644 --- a/src/Movement/DDA.h +++ b/src/Movement/DDA.h @@ -52,6 +52,7 @@ public: bool CanPauseAfter() const { return canPauseAfter; } bool CanPauseBefore() const { return canPauseBefore; } bool IsPrintingMove() const { return isPrintingMove; } // Return true if this involves both XY movement and extrusion + bool UsingStandardFeedrate() const { return usingStandardFeedrate; } DDAState GetState() const { return state; } DDA* GetNext() const { return next; } @@ -172,6 +173,7 @@ private: uint8_t xyMoving : 1; // True if movement along an X axis or the Y axis was requested, even it if's too small to do uint8_t goingSlow : 1; // True if we have slowed the movement because the Z probe is approaching its threshold uint8_t isLeadscrewAdjustmentMove : 1; // True if this is a leadscrews adjustment move + uint8_t usingStandardFeedrate : 1; // True if this move uses the standard feed rate }; uint16_t flags; // so that we can print all the flags at once for debugging }; @@ -239,7 +241,7 @@ inline void DDA::SetDriveCoordinate(int32_t a, size_t drive) endCoordinatesValid = false; } -#if HAS_SMART_DRIVERS +#if HAS_STALL_DETECT // Get the current full step interval for this axis or extruder inline uint32_t DDA::GetStepInterval(size_t axis, uint32_t microstepShift) const diff --git a/src/Movement/DriveMovement.cpp b/src/Movement/DriveMovement.cpp index 78120ab4..5afcf344 100644 --- a/src/Movement/DriveMovement.cpp +++ b/src/Movement/DriveMovement.cpp @@ -376,8 +376,10 @@ pre(nextStep < totalSteps; stepsTillRecalc == 0) + isqrt64((int64_t)(mp.cart.twoCsquaredTimesMmPerStepDivA * nextCalcStep) - mp.cart.fourMaxStepDistanceMinusTwoDistanceToStopTimesCsquaredDivA); } - stepInterval = (nextCalcStepTime - nextStepTime) >> shiftFactor; // calculate the time per step, ready for next time - + // When crossing between movement phases with high microstepping, due to rounding errors the next step may appear to be due before the last one + stepInterval = (nextCalcStepTime > nextStepTime) + ? (nextCalcStepTime - nextStepTime) >> shiftFactor // calculate the time per step, ready for next time + : 0; #if EVEN_STEPS nextStepTime = nextCalcStepTime - (stepsTillRecalc * stepInterval); #else @@ -496,8 +498,10 @@ pre(nextStep < totalSteps; stepsTillRecalc == 0) : dda.topSpeedTimesCdivAPlusDecelStartClocks; } - stepInterval = (nextCalcStepTime - nextStepTime) >> shiftFactor; // calculate the time per step, ready for next time - + // When crossing between movement phases with high microstepping, due to rounding errors the next step may appear to be due before the last one. + stepInterval = (nextCalcStepTime > nextStepTime) + ? (nextCalcStepTime - nextStepTime) >> shiftFactor // calculate the time per step, ready for next time + : 0; #if EVEN_STEPS nextStepTime = nextCalcStepTime - (stepsTillRecalc * stepInterval); #else diff --git a/src/Movement/DriveMovement.h b/src/Movement/DriveMovement.h index b33dfe14..8deb5b14 100644 --- a/src/Movement/DriveMovement.h +++ b/src/Movement/DriveMovement.h @@ -132,7 +132,7 @@ public: int32_t GetNetStepsLeft() const; int32_t GetNetStepsTaken() const; -#if HAS_SMART_DRIVERS +#if HAS_STALL_DETECT uint32_t GetStepInterval(uint32_t microstepShift) const; // Get the current full step interval for this axis or extruder #endif @@ -306,7 +306,7 @@ inline void DriveMovement::Release(DriveMovement *item) ++numFree; } -#if HAS_SMART_DRIVERS +#if HAS_STALL_DETECT // Get the current full step interval for this axis or extruder inline uint32_t DriveMovement::GetStepInterval(uint32_t microstepShift) const diff --git a/src/Movement/Kinematics/CoreBaseKinematics.cpp b/src/Movement/Kinematics/CoreBaseKinematics.cpp index 9d356fff..e4ab0529 100644 --- a/src/Movement/Kinematics/CoreBaseKinematics.cpp +++ b/src/Movement/Kinematics/CoreBaseKinematics.cpp @@ -35,7 +35,7 @@ bool CoreBaseKinematics::Configure(unsigned int mCode, GCodeBuffer& gb, const St seen = true; } } - if (!seen && !gb.Seen('K')) + if (!seen && !gb.Seen('S')) { reply.printf("Kinematics is %s with axis factors", GetName()); for (size_t axis = 0; axis < XYZ_AXES; ++axis) diff --git a/src/Movement/Move.cpp b/src/Movement/Move.cpp index 8a06e4ac..34c952af 100644 --- a/src/Movement/Move.cpp +++ b/src/Movement/Move.cpp @@ -433,6 +433,7 @@ bool Move::PausePrint(RestorePoint& rp) // // In general, we can pause after a move if it is the last segment and its end speed is slow enough. // We can pause before a move if it is the first segment in that move. + // The caller should set up rp.feedrate to the default feed rate for the file gcode source before calling this. const DDA * const savedDdaRingAddPointer = ddaRingAddPointer; bool pauseOkHere; @@ -486,7 +487,10 @@ bool Move::PausePrint(RestorePoint& rp) } dda = ddaRingAddPointer; - rp.feedRate = dda->GetRequestedSpeed(); + if (dda->UsingStandardFeedrate()) + { + rp.feedRate = dda->GetRequestedSpeed(); + } rp.virtualExtruderPosition = dda->GetVirtualExtruderPosition(); rp.filePos = dda->GetFilePosition(); diff --git a/src/Movement/Move.h b/src/Movement/Move.h index d9a83cb9..22c6a04d 100644 --- a/src/Movement/Move.h +++ b/src/Movement/Move.h @@ -125,7 +125,7 @@ public: bool WriteResumeSettings(FileStore *f) const; // Write settings for resuming the print -#if HAS_SMART_DRIVERS +#if HAS_STALL_DETECT uint32_t GetStepInterval(size_t axis, uint32_t microstepShift) const; // Get the current step interval for this axis or extruder #endif @@ -243,7 +243,7 @@ inline void Move::Interrupt() } } -#if HAS_SMART_DRIVERS +#if HAS_STALL_DETECT // Get the current step interval for this axis or extruder, or 0 if it is not moving // This is called from the stepper drivers SPI interface ISR diff --git a/src/Networking/HttpResponder.cpp b/src/Networking/HttpResponder.cpp index d29b8008..5095dea1 100644 --- a/src/Networking/HttpResponder.cpp +++ b/src/Networking/HttpResponder.cpp @@ -107,8 +107,12 @@ bool HttpResponder::Spin() return false; } + case ResponderState::processingRequest: + ProcessRequest(); + return true; + case ResponderState::gettingFileInfo: - (void)SendFileInfo(millis() - startedGettingFileInfoAt >= MaxFileInfoGetTime); + (void)SendFileInfo(millis() - startedProcessingRequestAt >= MaxFileInfoGetTime); return true; case ResponderState::uploading: @@ -486,11 +490,11 @@ bool HttpResponder::GetJsonResponse(const char* request, OutputBuffer *&response } else if (StringEquals(request, "status")) { - int type = 0; - if (GetKeyValue("type") != nullptr) + const char *typeString = GetKeyValue("type"); + if (typeString != nullptr) { // New-style JSON status responses - type = atoi(GetKeyValue("type")); + int type = SafeStrtol(typeString); if (type < 1 || type > 3) { type = 1; @@ -505,6 +509,13 @@ bool HttpResponder::GetJsonResponse(const char* request, OutputBuffer *&response OutputBuffer::Release(response); response = reprap.GetLegacyStatusResponse(1, 0); } + + if (response->HadOverflow()) + { + // We ran out of buffers. Release the buffers we have and return false. The caller will retry later. + OutputBuffer::ReleaseAll(response); + return false; + } } else if (StringEquals(request, "gcode") && GetKeyValue("gcode") != nullptr) { @@ -551,7 +562,6 @@ bool HttpResponder::GetJsonResponse(const char* request, OutputBuffer *&response // Simple rr_fileinfo call to get info about the file being printed filenameBeingProcessed[0] = 0; } - startedGettingFileInfoAt = millis(); responderState = ResponderState::gettingFileInfo; return false; } @@ -865,7 +875,7 @@ void HttpResponder::SendJsonResponse(const char* command) Authenticate(); } - // Update the authentication status and try handle "text/plain" requests here + // Update the authentication status and try to handle "text/plain" requests here if (CheckAuthenticated()) { if (StringEquals(command, "reply")) // rr_reply @@ -927,6 +937,11 @@ void HttpResponder::SendJsonResponse(const char* command) } } + // Note that when using RTOS the following response MUST be small enough to fit in a single buffer. + // This is because the current task may get suspended e.g. when reading from SD card to build a file list, + // so other tasks may allocate buffers meanwhile, and the previous mechanism for ensuring that there is sufficient + // buffer space remaining don't work. + // This response is currently about 230 bytes long in the worst case. outBuf->copy( "HTTP/1.1 200 OK\n" "Cache-Control: no-cache, no-store, must-revalidate\n" "Pragma: no-cache\n" @@ -941,26 +956,33 @@ void HttpResponder::SendJsonResponse(const char* command) Commit(keepOpen ? ResponderState::reading : ResponderState::free); } -// Process the message received so far. We have reached the end of the headers. -// Return true if the message is complete, false if we want to continue receiving data (i.e. postdata) +// Process the message received. We have reached the end of the headers. void HttpResponder::ProcessMessage() { if (reprap.Debug(moduleWebserver)) { - GetPlatform().MessageF(UsbMessage, "HTTP req, command words {"); + Platform& p = GetPlatform(); + p.MessageF(UsbMessage, "HTTP req, command words {"); for (size_t i = 0; i < numCommandWords; ++i) { - GetPlatform().MessageF(UsbMessage, " %s", commandWords[i]); + p.MessageF(UsbMessage, " %s", commandWords[i]); } - GetPlatform().Message(UsbMessage, " }, parameters {"); + p.Message(UsbMessage, " }, parameters {"); for (size_t i = 0; i < numQualKeys; ++i) { - GetPlatform().MessageF(UsbMessage, " %s=%s", qualifiers[i].key, qualifiers[i].value); + p.MessageF(UsbMessage, " %s=%s", qualifiers[i].key, qualifiers[i].value); } - GetPlatform().Message(UsbMessage, " }\n"); + p.Message(UsbMessage, " }\n"); } + responderState = ResponderState::processingRequest; + startedProcessingRequestAt = millis(); +} + +// Process the message received. We have reached the end of the headers. +void HttpResponder::ProcessRequest() +{ if (numCommandWords < 2) { RejectMessage("too few command words"); diff --git a/src/Networking/HttpResponder.h b/src/Networking/HttpResponder.h index 3b39a1cb..d19decba 100644 --- a/src/Networking/HttpResponder.h +++ b/src/Networking/HttpResponder.h @@ -80,6 +80,7 @@ private: void SendJsonResponse(const char* command); bool GetJsonResponse(const char* request, OutputBuffer *&response, bool& keepOpen); void ProcessMessage(); + void ProcessRequest(); void RejectMessage(const char* s, unsigned int code = 500); bool SendFileInfo(bool quitEarly); @@ -103,7 +104,7 @@ private: size_t numHeaderKeys; // number of keys we have found, <= maxHeaders // rr_fileinfo requests - uint32_t startedGettingFileInfoAt; // when we started trying to get file info + uint32_t startedProcessingRequestAt; // when we started processing the current HTTP request char filenameBeingProcessed[MaxFilenameLength]; // The filename being processed (for rr_fileinfo) // Keeping track of HTTP sessions diff --git a/src/Networking/NetworkResponder.h b/src/Networking/NetworkResponder.h index b43c02b9..8d3e2a92 100644 --- a/src/Networking/NetworkResponder.h +++ b/src/Networking/NetworkResponder.h @@ -39,6 +39,7 @@ protected: uploading, // uploading a file to SD card // HTTP responder additional states + processingRequest, gettingFileInfo, // getting file info // FTP responder additional states diff --git a/src/OutputMemory.cpp b/src/OutputMemory.cpp index 766ea98d..ce36b6b7 100644 --- a/src/OutputMemory.cpp +++ b/src/OutputMemory.cpp @@ -23,7 +23,12 @@ void OutputBuffer::Append(OutputBuffer *other) { last->next = other; last = other->last; - for(OutputBuffer *item = Next(); item != other; item = item->Next()) + if (other->hadOverflow) + { + hadOverflow = true; + } + + for (OutputBuffer *item = Next(); item != other; item = item->Next()) { item->last = last; } @@ -164,7 +169,8 @@ size_t OutputBuffer::cat(const char c) OutputBuffer *nextBuffer; if (!Allocate(nextBuffer)) { - // We cannot store any more data. Should never happen + // We cannot store any more data + hadOverflow = true; return 0; } nextBuffer->references = references; @@ -172,7 +178,7 @@ size_t OutputBuffer::cat(const char c) // Link the new item to this list last->next = nextBuffer; - for(OutputBuffer *item = this; item != nextBuffer; item = item->Next()) + for (OutputBuffer *item = this; item != nextBuffer; item = item->Next()) { item->last = nextBuffer; } @@ -202,6 +208,7 @@ size_t OutputBuffer::cat(const char *src, size_t len) if (!Allocate(nextBuffer)) { // We cannot store any more data, stop here + hadOverflow = true; break; } nextBuffer->references = references; @@ -372,8 +379,9 @@ bool OutputBuffer::WriteToFile(FileData& f) const buf->next = nullptr; buf->last = buf; buf->dataLength = buf->bytesRead = 0; - buf->references = 1; // Assume it's only used once by default + buf->references = 1; // assume it's only used once by default buf->isReferenced = false; + buf->hadOverflow = false; return true; } diff --git a/src/OutputMemory.h b/src/OutputMemory.h index d060ff4e..8660eb28 100644 --- a/src/OutputMemory.h +++ b/src/OutputMemory.h @@ -27,6 +27,7 @@ class OutputBuffer void Append(OutputBuffer *other); OutputBuffer *Next() const { return next; } bool IsReferenced() const { return isReferenced; } + bool HadOverflow() const { return hadOverflow; } void IncreaseReferences(size_t refs); const char *Data() const { return data; } @@ -94,6 +95,7 @@ class OutputBuffer size_t dataLength, bytesRead; bool isReferenced; + bool hadOverflow; volatile size_t references; static OutputBuffer * volatile freeOutputBuffers; // Messages may be sent by multiple tasks diff --git a/src/Platform.cpp b/src/Platform.cpp index 719a6252..e8031e2c 100644 --- a/src/Platform.cpp +++ b/src/Platform.cpp @@ -3191,7 +3191,7 @@ void Platform::EnableSharedFan(bool enable) // controls. This is the case if no thermostatic control is enabled and if the fan was configured at least once before. bool Platform::IsFanControllable(size_t fan) const { - return (fan < NUM_FANS) ? (!fans[fan].HasMonitoredHeaters() && fans[fan].IsConfigured()) : false; + return fan < NUM_FANS && !fans[fan].HasMonitoredHeaters() && fans[fan].IsConfigured(); } // Get current fan RPM @@ -3982,6 +3982,8 @@ bool Platform::SetExtrusionAncilliaryPwmPin(LogicalPin logicalPin, bool invert) return extrusionAncilliaryPwmPort.Set(logicalPin, PinAccess::pwm, invert); } +// CNC and laser support + void Platform::SetLaserPwm(float pwm) { laserPort.WriteAnalog(pwm); diff --git a/src/RepRap.cpp b/src/RepRap.cpp index 143201f2..fa1196fd 100644 --- a/src/RepRap.cpp +++ b/src/RepRap.cpp @@ -26,6 +26,7 @@ #if HAS_HIGH_SPEED_SD # include "sam/drivers/hsmci/hsmci.h" +# include "conf_sd_mmc.h" #endif #ifdef RTOS @@ -35,22 +36,32 @@ static TaskHandle_t hsmciTask = nullptr; // the task that is waiting for a HSMCI command to complete // Callback function from the hsmci driver, called while it is waiting for an SD card operation to complete -// 'st' is the set of bits in the HSMCI status register that the caller is interested in. +// 'stBits' is the set of bits in the HSMCI status register that the caller is interested in. // The caller keeps calling this function until at least one of those bits is set. -extern "C" void hsmciIdle(uint32_t st) +extern "C" void hsmciIdle(uint32_t stBits, uint32_t dmaBits) { - if ((HSMCI->HSMCI_SR & st) == 0) + if ( (HSMCI->HSMCI_SR & stBits) == 0 +#if SAME70 + && (XDMAC->XDMAC_CHID[CONF_HSMCI_XDMAC_CHANNEL].XDMAC_CIS & dmaBits) == 0 +#endif + ) { - // Suspend this task until we get an interrupt indicating that a status bit has been set + // Suspend this task until we get an interrupt indicating that a status bit that we are interested in has been set hsmciTask = xTaskGetCurrentTaskHandle(); - HSMCI->HSMCI_IER = st; - ulTaskNotifyTake(pdTRUE, 1000); + HSMCI->HSMCI_IER = stBits; +#if SAME70 + XDMAC->XDMAC_CHID[CONF_HSMCI_XDMAC_CHANNEL].XDMAC_CIE = dmaBits; +#endif + ulTaskNotifyTake(pdTRUE, 200); } } extern "C" void HSMCI_Handler() { HSMCI->HSMCI_IDR = 0xFFFFFFFF; // disable all HSMCI interrupts +#if SAME70 + XDMAC->XDMAC_CHID[CONF_HSMCI_XDMAC_CHANNEL].XDMAC_CID = 0xFFFFFFFF; +#endif if (hsmciTask != nullptr) { vTaskNotifyGiveFromISR(hsmciTask, nullptr); // wake up the task @@ -58,12 +69,18 @@ extern "C" void HSMCI_Handler() } } +#if SAME70 +extern "C" void XDMAC_handler() __attribute__ ((alias("HSMCI_Handler"))); +#endif + #else +// Non-RTOS code + // Callback function from the hsmci driver, called while it is waiting for an SD card operation to complete -// 'st' is the set of bits in the HSMCI status register that the caller is interested in. +// 'stBits' is the set of bits in the HSMCI status register that the caller is interested in. // The caller keeps calling this function until at least one of those bits is set. -extern "C" void hsmciIdle(uint32_t st) +extern "C" void hsmciIdle(uint32_t stBits, uint32_t dmaBits) { if (reprap.GetSpinningModule() != moduleNetwork) { @@ -200,6 +217,10 @@ void RepRap::Init() # ifdef RTOS HSMCI->HSMCI_IDR = 0xFFFFFFFF; // disable all HSMCI interrupts NVIC_EnableIRQ(HSMCI_IRQn); +# if SAME70 + XDMAC->XDMAC_CHID[CONF_HSMCI_XDMAC_CHANNEL].XDMAC_CID = 0xFFFFFFFF; // disable all XDMAC interrupts from the HSMCI channel + NVIC_EnableIRQ(XDMAC_IRQn); +# endif # endif #endif platform->MessageF(UsbMessage, "%s is up and running.\n", FIRMWARE_NAME); @@ -1912,7 +1933,9 @@ char RepRap::GetStatusCharacter() const return (processingConfig) ? 'C' // Reading the configuration file : (gCodes->IsFlashing()) ? 'F' // Flashing a new firmware binary : (IsStopped()) ? 'H' // Halted +#if HAS_VOLTAGE_MONITOR : (!platform->HasVinPower()) ? 'O' // Off i.e. powered down +#endif : (gCodes->IsPausing()) ? 'D' // Pausing / Decelerating : (gCodes->IsResuming()) ? 'R' // Resuming : (gCodes->IsDoingToolChange()) ? 'T' // Changing tool diff --git a/src/SAME70_TEST/Pins_SAME70_TEST.h b/src/SAME70_TEST/Pins_SAME70_TEST.h index ae46f694..fd210d45 100644 --- a/src/SAME70_TEST/Pins_SAME70_TEST.h +++ b/src/SAME70_TEST/Pins_SAME70_TEST.h @@ -114,6 +114,7 @@ constexpr Pin VssaSensePin = NoPin; // Digital pin number to turn the IR LED on (high) or off (low), also controls the DIAG LED constexpr Pin Z_PROBE_MOD_PIN = NoPin; +constexpr Pin DiagPin = NoPin; // TBD // Cooling fans constexpr size_t NUM_FANS = 1; diff --git a/src/Version.h b/src/Version.h index 774dbb81..3397d1cc 100644 --- a/src/Version.h +++ b/src/Version.h @@ -15,11 +15,11 @@ #endif #ifndef VERSION -# define VERSION "2.0" RTOSVER "beta1+" +# define VERSION "2.0" RTOSVER "beta2" #endif #ifndef DATE -# define DATE "2018-04-12b1" +# define DATE "2018-04-19b1" #endif #define AUTHORS "reprappro, dc42, chrishamm, t3p3, dnewman" |