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

github.com/Duet3D/RepRapFirmware.git - Unnamed repository; edit this file 'description' to name the repository.
summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
-rw-r--r--.cproject28
-rw-r--r--.settings/language.settings.xml18
-rw-r--r--.settings/org.eclipse.core.resources.prefs4
-rw-r--r--src/Alligator/Pins_Alligator.h7
-rw-r--r--src/BugList.txt2
-rw-r--r--src/Duet/Pins_Duet.h7
-rw-r--r--src/Duet3/GMAC/ethernet_sam.c (renamed from src/SAME70_TEST/GMAC/ethernet_sam.c)0
-rw-r--r--src/Duet3/GMAC/ethernet_sam.h (renamed from src/SAME70_TEST/GMAC/ethernet_sam.h)0
-rw-r--r--src/Duet3/GMAC/same70_gmac.c (renamed from src/SAME70_TEST/GMAC/same70_gmac.c)0
-rw-r--r--src/Duet3/GMAC/same70_gmac.h (renamed from src/SAME70_TEST/GMAC/same70_gmac.h)0
-rw-r--r--src/Duet3/Pins_Duet3.h (renamed from src/SAME70_TEST/Pins_SAME70_TEST.h)89
-rw-r--r--src/DuetM/Pins_DuetM.h7
-rw-r--r--src/DuetNG/Pins_DuetNG.h9
-rw-r--r--src/Fans/Fan.cpp18
-rw-r--r--src/GCodes/GCodes.cpp26
-rw-r--r--src/GCodes/GCodes.h2
-rw-r--r--src/GCodes/GCodes2.cpp22
-rw-r--r--src/Heating/Heat.cpp42
-rw-r--r--src/Heating/Heat.h42
-rw-r--r--src/Heating/HeaterProtection.cpp2
-rw-r--r--src/Heating/Pid.cpp2
-rw-r--r--src/Movement/Move.cpp4
-rw-r--r--src/Movement/Move.h4
-rw-r--r--src/Movement/StepperDrivers/TMC22xx.cpp4
-rw-r--r--src/Movement/StepperDrivers/TMC22xx.h2
-rw-r--r--src/Movement/StepperDrivers/TMC2660.cpp133
-rw-r--r--src/Movement/StepperDrivers/TMC2660.h2
-rw-r--r--src/Movement/StepperDrivers/TMC51xx.cpp617
-rw-r--r--src/Movement/StepperDrivers/TMC51xx.h60
-rw-r--r--src/Networking/ESP8266WiFi/WiFiInterface.cpp2
-rw-r--r--src/Networking/Network.cpp2
-rw-r--r--src/Networking/Network.h2
-rw-r--r--src/Pccb/Pins_Pccb.h11
-rw-r--r--src/Pins.h10
-rw-r--r--src/Platform.cpp257
-rw-r--r--src/Platform.h42
-rw-r--r--src/RADDS/Pins_RADDS.h7
-rw-r--r--src/RepRap.cpp13
-rw-r--r--src/RepRapFirmware.h20
-rw-r--r--src/Tools/Tool.cpp2
-rw-r--r--src/Tools/Tool.h6
-rw-r--r--src/Version.h2
42 files changed, 1275 insertions, 254 deletions
diff --git a/.cproject b/.cproject
index a6326278..a5c2784f 100644
--- a/.cproject
+++ b/.cproject
@@ -110,7 +110,7 @@
</toolChain>
</folderInfo>
<sourceEntries>
- <entry excluding="src/Pccb|src/Alligator|src/Duet/Lwip/lwip/src/core/ipv6|src/Duet/Lwip/lwip/test|src/SAME70_TEST|src/Display|src/Networking|src/DuetNG|src/DuetM|src/RADDS" flags="VALUE_WORKSPACE_PATH|RESOLVED" kind="sourcePath" name=""/>
+ <entry excluding="src/Alligator|src/Duet/Lwip/lwip/src/core/ipv6|src/Duet/Lwip/lwip/test|src/Duet3|src/Display|src/Networking|src/Pccb|src/DuetNG|src/DuetM|src/RADDS" flags="VALUE_WORKSPACE_PATH|RESOLVED" kind="sourcePath" name=""/>
</sourceEntries>
</configuration>
</storageModule>
@@ -220,7 +220,7 @@
</toolChain>
</folderInfo>
<sourceEntries>
- <entry excluding="src/Pccb|src/Alligator|src/SAME70_TEST|src/Display|src/Duet|src/Networking|src/DuetNG|src/DuetM" flags="VALUE_WORKSPACE_PATH|RESOLVED" kind="sourcePath" name=""/>
+ <entry excluding="src/Alligator|src/Duet3|src/Display|src/Duet|src/Networking|src/Pccb|src/DuetNG|src/DuetM" flags="VALUE_WORKSPACE_PATH|RESOLVED" kind="sourcePath" name=""/>
</sourceEntries>
</configuration>
</storageModule>
@@ -341,7 +341,7 @@
</toolChain>
</folderInfo>
<sourceEntries>
- <entry excluding="src/Pccb|src/Duet/Lwip/lwip/src/core/ipv6|src/Duet/Lwip/lwip/test|src/SAME70_TEST|src/Display|src/Networking|src/DuetNG|src/Alligator/Lwip/lwip/src/include/ipv6|src/Alligator/Lwip/lwip/test|src/DuetM|src/Duet/MCP4461|src/Alligator/Lwip/lwip/src/core/ipv6|src/RADDS" flags="VALUE_WORKSPACE_PATH|RESOLVED" kind="sourcePath" name=""/>
+ <entry excluding="src/Duet/Lwip/lwip/src/core/ipv6|src/Networking|src/DuetNG|src/Alligator/Lwip/lwip/src/include/ipv6|src/Alligator/Lwip/lwip/test|src/Duet/MCP4461|src/Duet/Lwip/lwip/test|src/Duet3|src/Display|src/Pccb|src/DuetM|src/Alligator/Lwip/lwip/src/core/ipv6|src/RADDS" flags="VALUE_WORKSPACE_PATH|RESOLVED" kind="sourcePath" name=""/>
</sourceEntries>
</configuration>
</storageModule>
@@ -461,7 +461,7 @@
</toolChain>
</folderInfo>
<sourceEntries>
- <entry excluding="src/Pccb|src/Alligator|src/SAME70_TEST|src/Display|src/Duet|src/Networking/LwipEthernet|src/DuetM|src/RADDS" flags="VALUE_WORKSPACE_PATH|RESOLVED" kind="sourcePath" name=""/>
+ <entry excluding="src/Alligator|src/Duet3|src/Display|src/Duet|src/Pccb|src/Networking/LwipEthernet|src/DuetM|src/RADDS" flags="VALUE_WORKSPACE_PATH|RESOLVED" kind="sourcePath" name=""/>
</sourceEntries>
</configuration>
</storageModule>
@@ -581,14 +581,14 @@
</toolChain>
</folderInfo>
<sourceEntries>
- <entry excluding="src/Pccb|src/Alligator|src/SAME70_TEST|src/Duet|src/Networking/ESP8266WiFi|src/Networking/LwipEthernet|src/DuetNG|src/RADDS" flags="VALUE_WORKSPACE_PATH|RESOLVED" kind="sourcePath" name=""/>
+ <entry excluding="src/Alligator|src/Duet3|src/Duet|src/Networking/ESP8266WiFi|src/Pccb|src/Networking/LwipEthernet|src/DuetNG|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.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">
+ <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="Duet3">
<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"/>
@@ -606,7 +606,7 @@
</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}}/${BuildArtifactFileBaseName}.elf ${workspace_loc:/${ProjName}/${ConfigName}}/${BuildArtifactFileBaseName}.bin">
+ <configuration artifactExtension="elf" artifactName="Duet3Firmware" 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="Duet3" parent="cdt.managedbuild.config.gnu.cross.exe.release" postannouncebuildStep="Generating binary file" postbuildStep="arm-none-eabi-objcopy -O binary ${workspace_loc:/${ProjName}/${ConfigName}}/${BuildArtifactFileBaseName}.elf ${workspace_loc:/${ProjName}/${ConfigName}}/${BuildArtifactFileBaseName}.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"/>
@@ -640,14 +640,14 @@
<listOptionValue builtIn="false" value="&quot;${workspace_loc:/${CoreName}/asf/sam/utils/preprocessor}&quot;"/>
<listOptionValue builtIn="false" value="&quot;${workspace_loc:/${CoreName}/asf/thirdparty/CMSIS/Include}&quot;"/>
<listOptionValue builtIn="false" value="&quot;${workspace_loc:/${CoreName}/variants/same70}&quot;"/>
- <listOptionValue builtIn="false" value="&quot;${workspace_loc:/${ProjName}/src/SAME70_TEST}&quot;"/>
+ <listOptionValue builtIn="false" value="&quot;${workspace_loc:/${ProjName}/src/Duet3}&quot;"/>
<listOptionValue builtIn="false" value="&quot;${workspace_loc:/${ProjName}/src/Networking/LwipEthernet}&quot;"/>
<listOptionValue builtIn="false" value="&quot;${workspace_loc:/${ProjName}/src/Networking/LwipEthernet/Lwip/src/include}&quot;"/>
</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"/>
+ <listOptionValue builtIn="false" value="DUET3"/>
</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"/>
@@ -695,7 +695,7 @@
<listOptionValue builtIn="false" value="&quot;${workspace_loc:/${CoreName}/asf/thirdparty/CMSIS/Include}&quot;"/>
<listOptionValue builtIn="false" value="&quot;${workspace_loc:/${CoreName}/variants/same70}&quot;"/>
<listOptionValue builtIn="false" value="&quot;${workspace_loc:/${ProjName}/src}&quot;"/>
- <listOptionValue builtIn="false" value="&quot;${workspace_loc:/${ProjName}/src/SAME70_TEST}&quot;"/>
+ <listOptionValue builtIn="false" value="&quot;${workspace_loc:/${ProjName}/src/Duet3}&quot;"/>
<listOptionValue builtIn="false" value="&quot;${workspace_loc:/${ProjName}/src/Networking}&quot;"/>
<listOptionValue builtIn="false" value="&quot;${workspace_loc:/${ProjName}/src/Networking/LwipEthernet}&quot;"/>
<listOptionValue builtIn="false" value="&quot;${workspace_loc:/${ProjName}/src/Networking/LwipEthernet/Lwip/src/include}&quot;"/>
@@ -706,7 +706,7 @@
<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="DUET3"/>
<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"/>
@@ -715,7 +715,7 @@
</toolChain>
</folderInfo>
<sourceEntries>
- <entry excluding="src/Pccb|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/Networking/W5500Ethernet|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=""/>
+ <entry excluding="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/Networking/W5500Ethernet|src/DuetNG/DuetEthernet/Wiznet/Internet/MQTT|src/Alligator|src/Display|src/Pccb|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>
@@ -834,7 +834,7 @@
</toolChain>
</folderInfo>
<sourceEntries>
- <entry excluding="src/DuetM|src/Display|src/Networking|src/Alligator|src/SAME70_TEST|src/Duet|src/Networking/ESP8266WiFi|src/Networking/LwipEthernet|src/DuetNG|src/RADDS" flags="VALUE_WORKSPACE_PATH|RESOLVED" kind="sourcePath" name=""/>
+ <entry excluding="src/Alligator|src/Duet3|src/Display|src/Duet|src/Networking|src/Networking/ESP8266WiFi|src/Networking/LwipEthernet|src/DuetNG|src/DuetM|src/RADDS" flags="VALUE_WORKSPACE_PATH|RESOLVED" kind="sourcePath" name=""/>
</sourceEntries>
</configuration>
</storageModule>
@@ -955,7 +955,7 @@
</toolChain>
</folderInfo>
<sourceEntries>
- <entry excluding="src/DuetM|src/Display|src/Networking|src/Alligator|src/SAME70_TEST|src/Duet|src/Networking/ESP8266WiFi|src/Networking/LwipEthernet|src/DuetNG|src/RADDS" flags="VALUE_WORKSPACE_PATH|RESOLVED" kind="sourcePath" name=""/>
+ <entry excluding="src/Alligator|src/Duet3|src/Display|src/Duet|src/Networking|src/Networking/ESP8266WiFi|src/Networking/LwipEthernet|src/DuetNG|src/DuetM|src/RADDS" flags="VALUE_WORKSPACE_PATH|RESOLVED" kind="sourcePath" name=""/>
</sourceEntries>
</configuration>
</storageModule>
diff --git a/.settings/language.settings.xml b/.settings/language.settings.xml
index 4f109f3e..0f715a87 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="-284248688145585500" id="org.eclipse.cdt.build.crossgcc.CrossGCCBuiltinSpecsDetector" keep-relative-paths="false" name="CDT Cross GCC Built-in Compiler Settings" parameter="${COMMAND} ${FLAGS} -E -P -v -dD &quot;${INPUTS}&quot;" prefer-non-shared="true">
+ <provider class="org.eclipse.cdt.internal.build.crossgcc.CrossGCCBuiltinSpecsDetector" console="false" env-hash="-1059782738354140179" id="org.eclipse.cdt.build.crossgcc.CrossGCCBuiltinSpecsDetector" keep-relative-paths="false" name="CDT Cross GCC Built-in Compiler Settings" parameter="${COMMAND} ${FLAGS} -E -P -v -dD &quot;${INPUTS}&quot;" prefer-non-shared="true">
<language-scope id="org.eclipse.cdt.core.gcc"/>
<language-scope id="org.eclipse.cdt.core.g++"/>
</provider>
@@ -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="-284248688145585500" id="org.eclipse.cdt.build.crossgcc.CrossGCCBuiltinSpecsDetector" keep-relative-paths="false" name="CDT Cross GCC Built-in Compiler Settings" parameter="${COMMAND} ${FLAGS} -E -P -v -dD &quot;${INPUTS}&quot;" prefer-non-shared="true">
+ <provider class="org.eclipse.cdt.internal.build.crossgcc.CrossGCCBuiltinSpecsDetector" console="false" env-hash="-1059782738354140179" id="org.eclipse.cdt.build.crossgcc.CrossGCCBuiltinSpecsDetector" keep-relative-paths="false" name="CDT Cross GCC Built-in Compiler Settings" parameter="${COMMAND} ${FLAGS} -E -P -v -dD &quot;${INPUTS}&quot;" prefer-non-shared="true">
<language-scope id="org.eclipse.cdt.core.gcc"/>
<language-scope id="org.eclipse.cdt.core.g++"/>
</provider>
@@ -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="-284248688145585500" id="org.eclipse.cdt.build.crossgcc.CrossGCCBuiltinSpecsDetector" keep-relative-paths="false" name="CDT Cross GCC Built-in Compiler Settings" parameter="${COMMAND} ${FLAGS} -E -P -v -dD &quot;${INPUTS}&quot;" prefer-non-shared="true">
+ <provider class="org.eclipse.cdt.internal.build.crossgcc.CrossGCCBuiltinSpecsDetector" console="false" env-hash="-1059782738354140179" id="org.eclipse.cdt.build.crossgcc.CrossGCCBuiltinSpecsDetector" keep-relative-paths="false" name="CDT Cross GCC Built-in Compiler Settings" parameter="${COMMAND} ${FLAGS} -E -P -v -dD &quot;${INPUTS}&quot;" prefer-non-shared="true">
<language-scope id="org.eclipse.cdt.core.gcc"/>
<language-scope id="org.eclipse.cdt.core.g++"/>
</provider>
@@ -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="-284248688145585500" id="org.eclipse.cdt.build.crossgcc.CrossGCCBuiltinSpecsDetector" keep-relative-paths="false" name="CDT Cross GCC Built-in Compiler Settings" parameter="${COMMAND} ${FLAGS} -E -P -v -dD &quot;${INPUTS}&quot;" prefer-non-shared="true">
+ <provider class="org.eclipse.cdt.internal.build.crossgcc.CrossGCCBuiltinSpecsDetector" console="false" env-hash="-1059782738354140179" id="org.eclipse.cdt.build.crossgcc.CrossGCCBuiltinSpecsDetector" keep-relative-paths="false" name="CDT Cross GCC Built-in Compiler Settings" parameter="${COMMAND} ${FLAGS} -E -P -v -dD &quot;${INPUTS}&quot;" prefer-non-shared="true">
<language-scope id="org.eclipse.cdt.core.gcc"/>
<language-scope id="org.eclipse.cdt.core.g++"/>
</provider>
@@ -49,18 +49,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="-284248688145585500" id="org.eclipse.cdt.build.crossgcc.CrossGCCBuiltinSpecsDetector" keep-relative-paths="false" name="CDT Cross GCC Built-in Compiler Settings" parameter="${COMMAND} ${FLAGS} -E -P -v -dD &quot;${INPUTS}&quot;" prefer-non-shared="true">
+ <provider class="org.eclipse.cdt.internal.build.crossgcc.CrossGCCBuiltinSpecsDetector" console="false" env-hash="-1059782738354140179" id="org.eclipse.cdt.build.crossgcc.CrossGCCBuiltinSpecsDetector" keep-relative-paths="false" name="CDT Cross GCC Built-in Compiler Settings" parameter="${COMMAND} ${FLAGS} -E -P -v -dD &quot;${INPUTS}&quot;" prefer-non-shared="true">
<language-scope id="org.eclipse.cdt.core.gcc"/>
<language-scope id="org.eclipse.cdt.core.g++"/>
</provider>
</extension>
</configuration>
- <configuration id="cdt.managedbuild.config.gnu.cross.exe.release.516195201.976458850.241502451.1275216290.274082366.1645191116.1852610203" name="SAME70_RTOS">
+ <configuration id="cdt.managedbuild.config.gnu.cross.exe.release.516195201.976458850.241502451.1275216290.274082366.1645191116.1852610203" name="Duet3">
<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="-284248688145585500" id="org.eclipse.cdt.build.crossgcc.CrossGCCBuiltinSpecsDetector" keep-relative-paths="false" name="CDT Cross GCC Built-in Compiler Settings" parameter="${COMMAND} ${FLAGS} -E -P -v -dD &quot;${INPUTS}&quot;" prefer-non-shared="true">
+ <provider class="org.eclipse.cdt.internal.build.crossgcc.CrossGCCBuiltinSpecsDetector" console="false" env-hash="-1059782738354140179" id="org.eclipse.cdt.build.crossgcc.CrossGCCBuiltinSpecsDetector" keep-relative-paths="false" name="CDT Cross GCC Built-in Compiler Settings" parameter="${COMMAND} ${FLAGS} -E -P -v -dD &quot;${INPUTS}&quot;" prefer-non-shared="true">
<language-scope id="org.eclipse.cdt.core.gcc"/>
<language-scope id="org.eclipse.cdt.core.g++"/>
</provider>
@@ -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="-284248688145585500" id="org.eclipse.cdt.build.crossgcc.CrossGCCBuiltinSpecsDetector" keep-relative-paths="false" name="CDT Cross GCC Built-in Compiler Settings" parameter="${COMMAND} ${FLAGS} -E -P -v -dD &quot;${INPUTS}&quot;" prefer-non-shared="true">
+ <provider class="org.eclipse.cdt.internal.build.crossgcc.CrossGCCBuiltinSpecsDetector" console="false" env-hash="-1059782738354140179" id="org.eclipse.cdt.build.crossgcc.CrossGCCBuiltinSpecsDetector" keep-relative-paths="false" name="CDT Cross GCC Built-in Compiler Settings" parameter="${COMMAND} ${FLAGS} -E -P -v -dD &quot;${INPUTS}&quot;" prefer-non-shared="true">
<language-scope id="org.eclipse.cdt.core.gcc"/>
<language-scope id="org.eclipse.cdt.core.g++"/>
</provider>
@@ -82,7 +82,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="-284248688145585500" id="org.eclipse.cdt.build.crossgcc.CrossGCCBuiltinSpecsDetector" keep-relative-paths="false" name="CDT Cross GCC Built-in Compiler Settings" parameter="${COMMAND} ${FLAGS} -E -P -v -dD &quot;${INPUTS}&quot;" prefer-non-shared="true">
+ <provider class="org.eclipse.cdt.internal.build.crossgcc.CrossGCCBuiltinSpecsDetector" console="false" env-hash="-1059782738354140179" id="org.eclipse.cdt.build.crossgcc.CrossGCCBuiltinSpecsDetector" keep-relative-paths="false" name="CDT Cross GCC Built-in Compiler Settings" parameter="${COMMAND} ${FLAGS} -E -P -v -dD &quot;${INPUTS}&quot;" prefer-non-shared="true">
<language-scope id="org.eclipse.cdt.core.gcc"/>
<language-scope id="org.eclipse.cdt.core.g++"/>
</provider>
diff --git a/.settings/org.eclipse.core.resources.prefs b/.settings/org.eclipse.core.resources.prefs
new file mode 100644
index 00000000..6ebe5254
--- /dev/null
+++ b/.settings/org.eclipse.core.resources.prefs
@@ -0,0 +1,4 @@
+eclipse.preferences.version=1
+encoding//src/Display/ST7920/glcd11x14.cpp=UTF-8
+encoding//src/Display/ST7920/glcd7x11.cpp=UTF-8
+encoding//src/Movement/StepperDrivers/TMC51xx.cpp=UTF-8
diff --git a/src/Alligator/Pins_Alligator.h b/src/Alligator/Pins_Alligator.h
index ba7d0c35..6cdc61ce 100644
--- a/src/Alligator/Pins_Alligator.h
+++ b/src/Alligator/Pins_Alligator.h
@@ -33,8 +33,9 @@ const size_t MaxDriversPerAxis = 4; // The maximum number of stepper drivers
// Initialization macro used in statements needing to initialize values in arrays of size MAX_AXES
#define AXES_(a,b,c,d,e,f,g,h,i) { a,b,c,d,e,f }
+constexpr size_t NumEndstops = 6; // The number of inputs we have for endstops, filament sensors etc.
// Alligator + Piggy module max 5 heaters
-constexpr size_t Heaters = 5; // The number of heaters in the machine; 0 is the heated bed even if there isn't one
+constexpr size_t NumHeaters = 5; // The number of heaters in the machine; 0 is the heated bed even if there isn't one
constexpr size_t NumExtraHeaterProtections = 4; // The number of extra heater protection instances
constexpr size_t NumThermistorInputs = 5;
@@ -66,7 +67,7 @@ const Pin MotorFaultDetectPin = 22;
// Alligator End-stop pinout mapping for RepRapFirmware:
// 5V SIGN SIGN GND , 5V SIGN SIGN GND, 5V SIGN SIGN GND
// X E0 Y E1 Z E2-Zprobe
-const Pin END_STOP_PINS[DRIVES] = { 33, 35, 38, 34, 37, 39, NoPin };
+const Pin END_STOP_PINS[NumEndstops] = { 33, 35, 38, 34, 37, 39 };
// SPI DAC Motor for Current Vref
const size_t MaxSpiDac = 2;
@@ -77,7 +78,7 @@ const Pin TEMP_SENSE_PINS[NumThermistorInputs] = { 1, 0, 2, 3, 4 }; // Analogue
// h1,h2,h3,h4: X2,8,9,X8 is hardware PWM
// b: X3 is not hardware PWM
-const Pin HEAT_ON_PINS[Heaters] = { X3, X2, 8, 9, X8 };
+const Pin HEAT_ON_PINS[NumHeaters] = { X3, X2, 8, 9, X8 };
// Default thermistor parameters
// Bed thermistor: http://uk.farnell.com/epcos/b57863s103f040/sensor-miniature-ntc-10k/dp/1299930?Ntt=129-9930
diff --git a/src/BugList.txt b/src/BugList.txt
index 9745763b..c8fa66b8 100644
--- a/src/BugList.txt
+++ b/src/BugList.txt
@@ -30,11 +30,13 @@ Implemented in 2.02beta1:
Remaining:
- [done, ok on DuetM, test on Duet2] No warning messages when TMC2224 drivers overheat, https://forum.duet3d.com/topic/6309/little-monster-s-hort-to-ground/13
+- G30 S-1 when no Z probe, https://forum.duet3d.com/topic/6510/a-couple-of-dwc-odd-things/2
- Command to copy output from the following commands to the log file?
- Track which devices use which pins
- Matt's display changes/other display fixes
- Hangprinter PRs
- PR to have any enabled driver report 50C
+- PR to allow endstop input number to be specified in M558
- M116 parameter to set allowed temperature difference
- M208 xaa:bb etc.
- M557 option to set number of X and Y points instead of limits and spacing
diff --git a/src/Duet/Pins_Duet.h b/src/Duet/Pins_Duet.h
index 5d9e193a..322840ae 100644
--- a/src/Duet/Pins_Duet.h
+++ b/src/Duet/Pins_Duet.h
@@ -28,7 +28,8 @@ constexpr size_t NumFirmwareUpdateModules = 1;
constexpr size_t DRIVES = 9; // The number of drives in the machine, including X, Y, and Z plus extruder drives
#define DRIVES_(a,b,c,d,e,f,g,h,i,j,k,l) { a,b,c,d,e,f,g,h,i }
-constexpr size_t Heaters = 7; // The number of heaters in the machine; 0 is the heated bed even if there isn't one
+constexpr size_t NumEndstops = 9; // The number of inputs we have for endstops, filament sensors etc.
+constexpr size_t NumHeaters = 7; // The number of heaters in the machine; 0 is the heated bed even if there isn't one
constexpr size_t NumExtraHeaterProtections = 4; // The number of extra heater protection instances
constexpr size_t NumThermistorInputs = 7;
@@ -59,7 +60,7 @@ constexpr Pin DIRECTION_PINS[DRIVES] = { 15, 26, 4, X3, 35, 53, 51, 48, X11 };
// Endstops
// RepRapFirmware only has a single endstop per axis.
// Gcode defines if it is a max ("high end") or min ("low end") endstop and sets if it is active HIGH or LOW.
-constexpr Pin END_STOP_PINS[DRIVES] = { 11, 28, 60, 31, 24, 46, 45, 44, X9 };
+constexpr Pin END_STOP_PINS[NumEndstops] = { 11, 28, 60, 31, 24, 46, 45, 44, X9 };
// Indices for motor current digipots (if any): first 4 are for digipot 1 (on duet), second 4 for digipot 2 (on expansion board)
constexpr uint8_t POT_WIPES[8] = { 1, 3, 2, 0, 1, 3, 2, 0 };
@@ -70,7 +71,7 @@ constexpr float STEPPER_DAC_VOLTAGE_OFFSET = -0.025; // Stepper motor curre
// HEATERS
constexpr Pin TEMP_SENSE_PINS[NumThermistorInputs] = { 5, 4, 0, 7, 8, 9, 11 }; // Analogue pin numbers
-constexpr Pin HEAT_ON_PINS[Heaters] = { 6, X5, X7, 7, 8, 9, X17 }; // Heater Channel 7 (pin X17) is shared with Fan1
+constexpr Pin HEAT_ON_PINS[NumHeaters] = { 6, X5, X7, 7, 8, 9, X17 }; // Heater Channel 7 (pin X17) is shared with Fan1
// Default thermistor parameters
// Bed thermistor: http://uk.farnell.com/epcos/b57863s103f040/sensor-miniature-ntc-10k/dp/1299930?Ntt=129-9930
diff --git a/src/SAME70_TEST/GMAC/ethernet_sam.c b/src/Duet3/GMAC/ethernet_sam.c
index c2329262..c2329262 100644
--- a/src/SAME70_TEST/GMAC/ethernet_sam.c
+++ b/src/Duet3/GMAC/ethernet_sam.c
diff --git a/src/SAME70_TEST/GMAC/ethernet_sam.h b/src/Duet3/GMAC/ethernet_sam.h
index 46de9e67..46de9e67 100644
--- a/src/SAME70_TEST/GMAC/ethernet_sam.h
+++ b/src/Duet3/GMAC/ethernet_sam.h
diff --git a/src/SAME70_TEST/GMAC/same70_gmac.c b/src/Duet3/GMAC/same70_gmac.c
index 0a8b18de..0a8b18de 100644
--- a/src/SAME70_TEST/GMAC/same70_gmac.c
+++ b/src/Duet3/GMAC/same70_gmac.c
diff --git a/src/SAME70_TEST/GMAC/same70_gmac.h b/src/Duet3/GMAC/same70_gmac.h
index 1cb25970..1cb25970 100644
--- a/src/SAME70_TEST/GMAC/same70_gmac.h
+++ b/src/Duet3/GMAC/same70_gmac.h
diff --git a/src/SAME70_TEST/Pins_SAME70_TEST.h b/src/Duet3/Pins_Duet3.h
index b73428a9..5b1a12d5 100644
--- a/src/SAME70_TEST/Pins_SAME70_TEST.h
+++ b/src/Duet3/Pins_Duet3.h
@@ -1,10 +1,10 @@
#ifndef PINS_SAME70_H__
#define PINS_SAME70_H__
-#define FIRMWARE_NAME "RepRapFirmware for SAME70"
-#define DEFAULT_BOARD_TYPE BoardType::SamE70TestBoard
+#define FIRMWARE_NAME "RepRapFirmware for Duet 3"
+#define DEFAULT_BOARD_TYPE BoardType::Duet3_10
const size_t NumFirmwareUpdateModules = 4; // 3 modules, plus one for manual upload to WiFi module (module 2 not used)
-#define IAP_FIRMWARE_FILE "SAME70Firmware.bin"
+#define IAP_FIRMWARE_FILE "Duet3Firmware.bin"
#define WIFI_FIRMWARE_FILE "DuetWiFiServer.bin"
#define IAP_UPDATE_FILE "iape70.bin" // need special build for SAME70
@@ -13,26 +13,44 @@ const size_t NumFirmwareUpdateModules = 4; // 3 modules, plus one for manual up
#define HAS_WIFI_NETWORKING 1
#define HAS_CPU_TEMP_SENSOR 1
#define HAS_HIGH_SPEED_SD 1
+
+//#define VARIANT_TMC5130 1
+
+#ifdef VARIANT_TMC5130
+# define SUPPORT_TMC51xx 1
+# define TMC51xx_USES_USART 1
+#else
+# define SUPPORT_TMC2660 1
+# define TMC2660_USES_USART 1
+#endif
+
#define HAS_VOLTAGE_MONITOR 0 // TBD
#define HAS_VREF_MONITOR 0 // TBD
-#define ACTIVE_LOW_HEAT_ON 0 // TBD
+#define ACTIVE_LOW_HEAT_ON 0
-#define SUPPORT_INKJET 0 // set nonzero to support inkjet control
-#define SUPPORT_ROLAND 0 // set nonzero to support Roland mill
-#define SUPPORT_SCANNER 0 // set zero to disable support for FreeLSS scanners
-#define SUPPORT_IOBITS 1 // set to support P parameter in G0/G1 commands
-#define SUPPORT_DHT_SENSOR 1 // set nonzero to support DHT temperature/humidity sensors
-#define SUPPORT_WORKPLACE_COORDINATES 1 // set nonzero to support G10 L2 and G53..59
+#define SUPPORT_INKJET 0 // set nonzero to support inkjet control
+#define SUPPORT_ROLAND 0 // set nonzero to support Roland mill
+#define SUPPORT_SCANNER 0 // set zero to disable support for FreeLSS scanners
+#define SUPPORT_IOBITS 1 // set to support P parameter in G0/G1 commands
+#define SUPPORT_DHT_SENSOR 1 // set nonzero to support DHT temperature/humidity sensors
+#define SUPPORT_WORKPLACE_COORDINATES 1 // set nonzero to support G10 L2 and G53..59
-#define USE_CACHE 0 // Cache controller has some problems on the SAME70
+#define USE_CACHE 0 // Cache controller disabled for now
// The physical capabilities of the machine
-const size_t DRIVES = 6; // The maximum number of drives supported by the electronics
-const size_t MaxSmartDrivers = 6; // The maximum number of smart drivers
-#define DRIVES_(a,b,c,d,e,f,g,h,i,j,k,l) { a,b,c,d,e,f }
+#ifdef VARIANT_TMC5130
+constexpr size_t DRIVES = 6; // The maximum number of drives supported by the electronics
+constexpr size_t MaxSmartDrivers = 6; // The maximum number of smart drivers
+# define DRIVES_(a,b,c,d,e,f,g,h,i,j,k,l) { a,b,c,d,e,f }
+#else
+constexpr size_t DRIVES = 5; // The maximum number of drives supported by the electronics
+constexpr size_t MaxSmartDrivers = 5; // The maximum number of smart drivers
+# define DRIVES_(a,b,c,d,e,f,g,h,i,j,k,l) { a,b,c,d,e }
+#endif
-constexpr size_t Heaters = 4; // The number of heaters in the machine; 0 is the heated bed even if there isn't one
+constexpr size_t NumEndstops = 6; // The number of inputs we have for endstops, filament sensors etc.
+constexpr size_t NumHeaters = 4; // The number of heaters in the machine; 0 is the heated bed even if there isn't one
constexpr size_t NumExtraHeaterProtections = 8; // The number of extra heater protection instances
constexpr size_t NumThermistorInputs = 4;
@@ -55,22 +73,51 @@ constexpr size_t NUM_SERIAL_CHANNELS = 2; // The number of serial IO channels
// The numbers of entries in each array must correspond with the values of DRIVES, AXES, or HEATERS. Set values to NoPin to flag unavailability.
// DRIVES
-constexpr Pin GlobalTmcEnablePin = NoPin; // The pin that drives ENN of all TMC2660 drivers on production boards (on pre-production boards they are grounded)
+
+#ifdef VARIANT_TMC5130
+
constexpr Pin ENABLE_PINS[DRIVES] = { NoPin, NoPin, NoPin, NoPin, NoPin, NoPin };
constexpr Pin STEP_PINS[DRIVES] = { NoPin, NoPin, NoPin, NoPin, NoPin, NoPin };
constexpr Pin DIRECTION_PINS[DRIVES] = { NoPin, NoPin, NoPin, NoPin, NoPin, NoPin };
-constexpr Pin DueX_SG = NoPin; // DueX stallguard detect pin (TBD)
-constexpr Pin DueX_INT = NoPin; // DueX interrupt pin (TBD)
+// Pin assignments etc. using USART1 in SPI mode
+constexpr Pin GlobalTmc51xxEnablePin = NoPin; // The pin that drives ENN of all TMC drivers
+Usart * const USART_TMC51xx = USART1;
+constexpr uint32_t ID_TMC51xx_SPI = ID_USART1;
+constexpr IRQn TMC51xx_SPI_IRQn = USART1_IRQn;
+# define TMC51xx_SPI_Handler USART1_Handler
+
+constexpr Pin TMC51xxMosiPin = NoPin;
+constexpr Pin TMC51xxMisoPin = NoPin;
+constexpr Pin TMC51xxSclkPin = NoPin;
+
+#else
+
+constexpr Pin ENABLE_PINS[DRIVES] = { NoPin, NoPin, NoPin, NoPin, NoPin };
+constexpr Pin STEP_PINS[DRIVES] = { NoPin, NoPin, NoPin, NoPin, NoPin };
+constexpr Pin DIRECTION_PINS[DRIVES] = { NoPin, NoPin, NoPin, NoPin, NoPin };
+
+// Pin assignments etc. using USART1 in SPI mode
+constexpr Pin GlobalTmc2660EnablePin = NoPin; // The pin that drives ENN of all TMC drivers
+Usart * const USART_TMC2660 = USART1;
+constexpr uint32_t ID_TMC2660_SPI = ID_USART1;
+constexpr IRQn TMC2660_SPI_IRQn = USART1_IRQn;
+# define TMC2660_SPI_Handler USART1_Handler
+
+constexpr Pin TMC2660MosiPin = NoPin;
+constexpr Pin TMC2660MisoPin = NoPin;
+constexpr Pin TMC2660SclkPin = NoPin;
+
+#endif
// Endstops
// RepRapFirmware only has a single endstop per axis.
// Gcode defines if it is a max ("high end") or min ("low end") endstop and sets if it is active HIGH or LOW.
-constexpr Pin END_STOP_PINS[DRIVES] = { NoPin, NoPin, NoPin, NoPin, NoPin, NoPin };
+constexpr Pin END_STOP_PINS[NumEndstops] = { NoPin, NoPin, NoPin, NoPin, NoPin, NoPin };
// Heater and thermistors
-constexpr Pin TEMP_SENSE_PINS[NumThermistorInputs] = { 66, 86, 48, 65 }; // Thermistor pin numbers (labelled AD1-2 and AD4-5 on test board, but AD5 has a 0R resistor missing)
-constexpr Pin HEAT_ON_PINS[Heaters] = { NoPin, NoPin, NoPin, NoPin }; // Heater pin numbers (TBD)
+constexpr Pin TEMP_SENSE_PINS[NumThermistorInputs] = { 66, 86, 48, 65 }; // Thermistor pin numbers (labelled AD1-2 and AD4-5 on eval board, but AD5 has a 0R resistor missing)
+constexpr Pin HEAT_ON_PINS[NumHeaters] = { NoPin, NoPin, NoPin, NoPin }; // Heater pin numbers (TBD)
// Default thermistor parameters
constexpr float BED_R25 = 100000.0;
diff --git a/src/DuetM/Pins_DuetM.h b/src/DuetM/Pins_DuetM.h
index bc489001..f54bd298 100644
--- a/src/DuetM/Pins_DuetM.h
+++ b/src/DuetM/Pins_DuetM.h
@@ -41,7 +41,8 @@ constexpr size_t DRIVES = 7; // The maximum number of drives supported by t
constexpr size_t MaxSmartDrivers = 7; // The maximum number of smart drivers
#define DRIVES_(a,b,c,d,e,f,g,h,i,j,k,l) { a,b,c,d,e,f,g }
-constexpr size_t Heaters = 3; // The number of heaters/thermistors in the machine. Duet M has 3 heaters but 4 thermistors.
+constexpr size_t NumEndstops = 5; // The number of inputs we have for endstops, filament sensors etc.
+constexpr size_t NumHeaters = 3; // The number of heaters/thermistors in the machine. Duet M has 3 heaters but 4 thermistors.
constexpr size_t NumExtraHeaterProtections = 4; // The number of extra heater protection instances
constexpr size_t NumThermistorInputs = 4;
@@ -89,10 +90,10 @@ constexpr Pin TMC22xxMuxPins[3] = { 50, 52, 53 }; // Pins that control the UART
// Endstops
// RepRapFirmware only has a single endstop per axis.
// Gcode defines if it is a max ("high end") or min ("low end") endstop and sets if it is active HIGH or LOW.
-constexpr Pin END_STOP_PINS[DRIVES] = { 24, 32, 46, 25, 43, NoPin, NoPin };
+constexpr Pin END_STOP_PINS[NumEndstops] = { 24, 32, 46, 25, 43 };
// Heaters and thermistors
-constexpr Pin HEAT_ON_PINS[Heaters] = { 36, 37, 16 }; // Heater pin numbers
+constexpr Pin HEAT_ON_PINS[NumHeaters] = { 36, 37, 16 }; // Heater pin numbers
constexpr Pin TEMP_SENSE_PINS[NumThermistorInputs] = { 20, 26, 66, 27 }; // Thermistor pin numbers
constexpr Pin VssaSensePin = 19;
constexpr Pin VrefSensePin = 17;
diff --git a/src/DuetNG/Pins_DuetNG.h b/src/DuetNG/Pins_DuetNG.h
index 92151b1e..34d37893 100644
--- a/src/DuetNG/Pins_DuetNG.h
+++ b/src/DuetNG/Pins_DuetNG.h
@@ -38,7 +38,8 @@ constexpr size_t DRIVES = 12; // The maximum number of drives supported by
constexpr size_t MaxSmartDrivers = 10; // The maximum number of smart drivers
#define DRIVES_(a,b,c,d,e,f,g,h,i,j,k,l) { a,b,c,d,e,f,g,h,i,j,k,l }
-constexpr size_t Heaters = 8; // The number of heaters in the machine; 0 is the heated bed even if there isn't one
+constexpr size_t NumEndstops = 12; // The number of inputs we have for endstops, filament sensors etc.
+constexpr size_t NumHeaters = 8; // The number of heaters in the machine; 0 is the heated bed even if there isn't one
constexpr size_t NumExtraHeaterProtections = 8; // The number of extra heater protection instances
constexpr size_t NumThermistorInputs = 8;
@@ -85,12 +86,12 @@ constexpr Pin DueX_INT = 17; // DueX interrupt pin = PA17 (was E6_STOP)
// Endstops
// RepRapFirmware only has a single endstop per axis.
// Gcode defines if it is a max ("high end") or min ("low end") endstop and sets if it is active HIGH or LOW.
-constexpr Pin END_STOP_PINS[DRIVES] = { 46, 02, 93, 74, 48, 96, 97, 98, 99, 17, 39, 8 };
-constexpr Pin DUEX_END_STOP_PINS[5] = { 200, 203, 202, 201, 213 }; // these replace endstops 5-9 if a DueX is present
+constexpr Pin END_STOP_PINS[NumEndstops] = { 46, 02, 93, 74, 48, 96, 97, 98, 99, 17, 39, 8 };
+constexpr Pin DUEX_END_STOP_PINS[5] = { 200, 203, 202, 201, 213 }; // these replace endstops 5-9 if a DueX is present
// HEATERS
constexpr Pin TEMP_SENSE_PINS[NumThermistorInputs] = { 45, 47, 44, 61, 62, 63, 59, 18 }; // Thermistor pin numbers
-constexpr Pin HEAT_ON_PINS[Heaters] = { 19, 20, 16, 35, 37, 40, 43, 15 }; // Heater pin numbers (heater 7 pin TBC)
+constexpr Pin HEAT_ON_PINS[NumHeaters] = { 19, 20, 16, 35, 37, 40, 43, 15 }; // Heater pin numbers (heater 7 pin TBC)
// Default thermistor parameters
constexpr float BED_R25 = 100000.0;
diff --git a/src/Fans/Fan.cpp b/src/Fans/Fan.cpp
index 40f419f3..7e90f538 100644
--- a/src/Fans/Fan.cpp
+++ b/src/Fans/Fan.cpp
@@ -129,7 +129,7 @@ bool Fan::Configure(unsigned int mcode, int fanNum, GCodeBuffer& gb, const Strin
if (gb.Seen('H')) // Set thermostatically-controlled heaters
{
seen = true;
- int32_t heaters[Heaters + MaxVirtualHeaters]; // signed because we use H-1 to disable thermostatic mode
+ int32_t heaters[NumHeaters + MaxVirtualHeaters]; // signed because we use H-1 to disable thermostatic mode
size_t numH = ARRAY_SIZE(heaters);
gb.GetIntArray(heaters, numH, false);
@@ -138,14 +138,14 @@ bool Fan::Configure(unsigned int mcode, int fanNum, GCodeBuffer& gb, const Strin
for (size_t h = 0; h < numH; ++h)
{
const int hnum = heaters[h];
- if (hnum >= 0 && hnum < (int)Heaters)
+ if (hnum >= 0 && hnum < (int)NumHeaters)
{
SetBit(heatersMonitored, (unsigned int)hnum);
}
else if (hnum >= (int)FirstVirtualHeater && hnum < (int)(FirstVirtualHeater + MaxVirtualHeaters))
{
// Heaters 100, 101... are virtual heaters i.e. CPU and driver temperatures
- SetBit(heatersMonitored, Heaters + (unsigned int)hnum - FirstVirtualHeater);
+ SetBit(heatersMonitored, NumHeaters + (unsigned int)hnum - FirstVirtualHeater);
}
}
if (heatersMonitored != 0)
@@ -191,11 +191,11 @@ bool Fan::Configure(unsigned int mcode, int fanNum, GCodeBuffer& gb, const Strin
if (heatersMonitored != 0)
{
reply.catf(", temperature: %.1f:%.1fC, heaters:", (double)triggerTemperatures[0], (double)triggerTemperatures[1]);
- for (unsigned int i = 0; i < Heaters + MaxVirtualHeaters; ++i)
+ for (unsigned int i = 0; i < NumHeaters + MaxVirtualHeaters; ++i)
{
if (IsBitSet(heatersMonitored, i))
{
- reply.catf(" %u", (i < Heaters) ? i : FirstVirtualHeater + i - Heaters);
+ reply.catf(" %u", (i < NumHeaters) ? i : FirstVirtualHeater + i - NumHeaters);
}
}
reply.catf(", current speed: %d%%:", (int)(lastVal * 100.0));
@@ -264,21 +264,21 @@ void Fan::Refresh()
{
reqVal = 0.0;
const bool bangBangMode = (triggerTemperatures[1] <= triggerTemperatures[0]);
- for (size_t h = 0; h < Heaters + MaxVirtualHeaters; ++h)
+ for (size_t h = 0; h < NumHeaters + MaxVirtualHeaters; ++h)
{
// Check if this heater is both monitored by this fan and in use
if ( IsBitSet(heatersMonitored, h)
- && (h < reprap.GetToolHeatersInUse() || (h >= Heaters && h < Heaters + MaxVirtualHeaters) || reprap.GetHeat().IsBedOrChamberHeater(h))
+ && (h < reprap.GetToolHeatersInUse() || (h >= NumHeaters && h < NumHeaters + MaxVirtualHeaters) || reprap.GetHeat().IsBedOrChamberHeater(h))
)
{
// This heater is both monitored and potentially active
- if (h < Heaters && reprap.GetHeat().IsTuning(h))
+ if (h < NumHeaters && reprap.GetHeat().IsTuning(h))
{
reqVal = 1.0; // when turning the PID for a monitored heater, turn the fan on
}
else
{
- const size_t heaterHumber = (h >= Heaters) ? (h - Heaters) + FirstVirtualHeater : h;
+ const size_t heaterHumber = (h >= NumHeaters) ? (h - NumHeaters) + FirstVirtualHeater : h;
TemperatureError err;
const float ht = reprap.GetHeat().GetTemperature(heaterHumber, err);
if (err != TemperatureError::success || ht < BAD_LOW_TEMPERATURE || ht >= triggerTemperatures[1])
diff --git a/src/GCodes/GCodes.cpp b/src/GCodes/GCodes.cpp
index 22f41cd7..88c1c9fb 100644
--- a/src/GCodes/GCodes.cpp
+++ b/src/GCodes/GCodes.cpp
@@ -1785,7 +1785,7 @@ bool GCodes::IsHeatingUp() const
&& ((num = fileGCode->GetCommandNumber()) == 109 || num == 116 || num == 190 || num == 191);
}
-#if HAS_VOLTAGE_MONITOR || HAS_SMART_DRIVERS
+#if HAS_VOLTAGE_MONITOR || HAS_STALL_DETECT
// Do an emergency pause following loss of power or a motor stall returning true if successful, false if needs to be retried
bool GCodes::DoEmergencyPause()
@@ -1798,7 +1798,7 @@ bool GCodes::DoEmergencyPause()
// Save the resume info, stop movement immediately and run the low voltage pause script to lift the nozzle etc.
GrabMovement(*autoPauseGCode);
- const bool movesSkipped = reprap.GetMove().LowPowerPause(pauseRestorePoint);
+ const bool movesSkipped = reprap.GetMove().LowPowerOrStallPause(pauseRestorePoint);
if (movesSkipped)
{
// The PausePrint call has filled in the restore point with machine coordinates
@@ -3356,7 +3356,7 @@ GCodeResult GCodes::SetOrReportOffsets(GCodeBuffer &gb, const StringRef& reply)
settingTemps = true;
if (simulationMode == 0)
{
- float standby[Heaters];
+ float standby[NumHeaters];
gb.GetFloatArray(standby, hCount, true);
for (size_t h = 0; h < hCount; ++h)
{
@@ -3369,7 +3369,7 @@ GCodeResult GCodes::SetOrReportOffsets(GCodeBuffer &gb, const StringRef& reply)
settingTemps = true;
if (simulationMode == 0)
{
- float active[Heaters];
+ float active[NumHeaters];
gb.GetFloatArray(active, hCount, true);
for (size_t h = 0; h < hCount; ++h)
{
@@ -3448,8 +3448,8 @@ bool GCodes::ManageTool(GCodeBuffer& gb, const StringRef& reply)
}
// Check heaters
- int32_t heaters[Heaters];
- size_t hCount = Heaters;
+ int32_t heaters[NumHeaters];
+ size_t hCount = NumHeaters;
if (gb.Seen('H'))
{
gb.GetIntArray(heaters, hCount, false);
@@ -3780,7 +3780,7 @@ bool GCodes::SetHeaterProtection(GCodeBuffer& gb, const StringRef& reply)
const int index = (gb.Seen('P'))
? gb.GetIValue()
: (gb.Seen('H')) ? gb.GetIValue() : 1; // default to extruder 1 if no heater number provided
- if ((index < 0 || index >= (int)Heaters) && (index < (int)FirstExtraHeaterProtection || index >= (int)(FirstExtraHeaterProtection + NumExtraHeaterProtections)))
+ if ((index < 0 || index >= (int)NumHeaters) && (index < (int)FirstExtraHeaterProtection || index >= (int)(FirstExtraHeaterProtection + NumExtraHeaterProtections)))
{
reply.printf("Invalid heater protection item '%d'", index);
return true;
@@ -3793,7 +3793,7 @@ bool GCodes::SetHeaterProtection(GCodeBuffer& gb, const StringRef& reply)
if (gb.Seen('P') && gb.Seen('H'))
{
const int heater = gb.GetIValue();
- if (heater > (int)Heaters) // allow negative values to disable heater protection
+ if (heater > (int)NumHeaters) // allow negative values to disable heater protection
{
reply.printf("Invalid heater number '%d'", heater);
return true;
@@ -3807,7 +3807,7 @@ bool GCodes::SetHeaterProtection(GCodeBuffer& gb, const StringRef& reply)
if (gb.Seen('X'))
{
const int heater = gb.GetIValue();
- if ((heater < 0 || heater > (int)Heaters) && (heater < (int)FirstVirtualHeater || heater >= (int)(FirstVirtualHeater + MaxVirtualHeaters)))
+ if ((heater < 0 || heater > (int)NumHeaters) && (heater < (int)FirstVirtualHeater || heater >= (int)(FirstVirtualHeater + MaxVirtualHeaters)))
{
reply.printf("Invalid heater number '%d'", heater);
return true;
@@ -3912,7 +3912,7 @@ void GCodes::SetPidParameters(GCodeBuffer& gb, int heater, const StringRef& repl
heater = gb.GetIValue();
}
- if (heater >= 0 && heater < (int)Heaters)
+ if (heater >= 0 && heater < (int)NumHeaters)
{
const FopDt& model = reprap.GetHeat().GetHeaterModel(heater);
M301PidParameters pp = model.GetM301PidParameters(false);
@@ -3946,7 +3946,7 @@ GCodeResult GCodes::SetHeaterParameters(GCodeBuffer& gb, const StringRef& reply)
if (gb.Seen('P'))
{
const int heater = gb.GetIValue();
- if ((heater >= 0 && heater < (int)Heaters) || (heater >= (int)FirstVirtualHeater && heater < (int)(FirstVirtualHeater + MaxVirtualHeaters)))
+ if ((heater >= 0 && heater < (int)NumHeaters) || (heater >= (int)FirstVirtualHeater && heater < (int)(FirstVirtualHeater + MaxVirtualHeaters)))
{
Heat& heat = reprap.GetHeat();
const int oldChannel = heat.GetHeaterChannel(heater);
@@ -3956,7 +3956,7 @@ GCodeResult GCodes::SetHeaterParameters(GCodeBuffer& gb, const StringRef& reply)
if (!seen && oldChannel < 0)
{
// For backwards compatibility, if no sensor has been configured on this channel then assume the thermistor normally associated with the heater
- if (heater < (int)Heaters && (gb.Seen('R') || gb.Seen('T') || gb.Seen('B'))) // if it has a thermistor and we are trying to configure it
+ if (heater < (int)NumHeaters && (gb.Seen('R') || gb.Seen('T') || gb.Seen('B'))) // if it has a thermistor and we are trying to configure it
{
channel = heater;
}
@@ -4808,7 +4808,7 @@ void GCodes::GrabResource(const GCodeBuffer& gb, Resource r)
bool GCodes::LockHeater(const GCodeBuffer& gb, int heater)
{
- if (heater >= 0 && heater < (int)Heaters)
+ if (heater >= 0 && heater < (int)NumHeaters)
{
return LockResource(gb, HeaterResourceBase + heater);
}
diff --git a/src/GCodes/GCodes.h b/src/GCodes/GCodes.h
index bce37642..7afa207f 100644
--- a/src/GCodes/GCodes.h
+++ b/src/GCodes/GCodes.h
@@ -237,7 +237,7 @@ private:
static const Resource MoveResource = 0; // Movement system, including canned cycle variables
static const Resource FileSystemResource = 1; // Non-sharable parts of the file system
static const Resource HeaterResourceBase = 2;
- static const Resource FanResourceBase = HeaterResourceBase + Heaters;
+ static const Resource FanResourceBase = HeaterResourceBase + NumHeaters;
static const size_t NumResources = FanResourceBase + NUM_FANS;
static_assert(NumResources <= 32, "Too many resources to keep a bitmap of them in class GCodeMachineState");
diff --git a/src/GCodes/GCodes2.cpp b/src/GCodes/GCodes2.cpp
index d0e1e392..81a5599c 100644
--- a/src/GCodes/GCodes2.cpp
+++ b/src/GCodes/GCodes2.cpp
@@ -33,10 +33,12 @@
#if SUPPORT_TMC2660
# include "Movement/StepperDrivers/TMC2660.h"
#endif
-
#if SUPPORT_TMC22xx
# include "Movement/StepperDrivers/TMC22xx.h"
#endif
+#if SUPPORT_TMC51xx
+# include "Movement/StepperDrivers/TMC51xx.h"
+#endif
#if SUPPORT_12864_LCD
# include "Display/Display.h"
@@ -1459,8 +1461,8 @@ bool GCodes::HandleMcode(GCodeBuffer& gb, const StringRef& reply)
if (gb.Seen('H'))
{
// Wait for specified heaters to be ready
- uint32_t heaters[Heaters];
- size_t heaterCount = Heaters;
+ uint32_t heaters[NumHeaters];
+ size_t heaterCount = NumHeaters;
gb.GetUnsignedArray(heaters, heaterCount, false);
for (size_t i = 0; i < heaterCount; i++)
@@ -1644,7 +1646,7 @@ bool GCodes::HandleMcode(GCodeBuffer& gb, const StringRef& reply)
{
heater = -1;
}
- else if (heater >= (int)Heaters)
+ else if (heater >= (int)NumHeaters)
{
reply.printf("Invalid heater number '%d'", heater);
result = GCodeResult::error;
@@ -2289,7 +2291,7 @@ bool GCodes::HandleMcode(GCodeBuffer& gb, const StringRef& reply)
: reprap.GetHeat().IsChamberHeater(heater) ? 50.0
: 200.0;
const float maxPwm = (gb.Seen('P')) ? gb.GetFValue() : reprap.GetHeat().GetHeaterModel(heater).GetMaxPwm();
- if (heater >= Heaters)
+ if (heater >= NumHeaters)
{
reply.copy("Bad heater number in M303 command");
}
@@ -2324,7 +2326,7 @@ bool GCodes::HandleMcode(GCodeBuffer& gb, const StringRef& reply)
if (gb.Seen('H'))
{
const unsigned int heater = gb.GetUIValue();
- if (heater < Heaters)
+ if (heater < NumHeaters)
{
const FopDt& model = reprap.GetHeat().GetHeaterModel(heater);
bool seen = false;
@@ -3014,7 +3016,7 @@ bool GCodes::HandleMcode(GCodeBuffer& gb, const StringRef& reply)
if (gb.Seen('P'))
{
const unsigned int heater = gb.GetUIValue();
- if (heater < Heaters)
+ if (heater < NumHeaters)
{
reprap.ClearTemperatureFault(heater);
}
@@ -3027,7 +3029,7 @@ bool GCodes::HandleMcode(GCodeBuffer& gb, const StringRef& reply)
else
{
// Clear all heater faults
- for (unsigned int heater = 0; heater < Heaters; ++heater)
+ for (unsigned int heater = 0; heater < NumHeaters; ++heater)
{
reprap.ClearTemperatureFault(heater);
}
@@ -3246,7 +3248,7 @@ bool GCodes::HandleMcode(GCodeBuffer& gb, const StringRef& reply)
if (gb.Seen('H'))
{
const unsigned heater = gb.GetUIValue();
- if (heater < Heaters)
+ if (heater < NumHeaters)
{
bool seenValue = false;
float maxTempExcursion, maxFaultTime;
@@ -3344,7 +3346,7 @@ bool GCodes::HandleMcode(GCodeBuffer& gb, const StringRef& reply)
if (gb.Seen('P'))
{
const unsigned int heater = gb.GetUIValue();
- if (heater < Heaters)
+ if (heater < NumHeaters)
{
reply.printf("Average heater %u PWM: %.3f", heater, (double)reprap.GetHeat().GetAveragePWM(heater));
}
diff --git a/src/Heating/Heat.cpp b/src/Heating/Heat.cpp
index 3a05527c..3fb88247 100644
--- a/src/Heating/Heat.cpp
+++ b/src/Heating/Heat.cpp
@@ -92,7 +92,7 @@ void Heat::Init()
const float tempLimit = (IsBedOrChamberHeater(index)) ? DefaultBedTemperatureLimit : DefaultExtruderTemperatureLimit;
prot->Init(tempLimit);
- if (index < Heaters)
+ if (index < NumHeaters)
{
pids[index]->SetHeaterProtection(prot);
}
@@ -111,7 +111,7 @@ void Heat::Init()
pids[heater]->Init(DefaultBedHeaterGain, DefaultBedHeaterTimeConstant, DefaultBedHeaterDeadTime, false, false);
}
#if defined(DUET_06_085)
- else if (heater == Heaters - 1)
+ else if (heater == NumHeaters - 1)
{
// On the Duet 085, the heater 6 pin is also the fan 1 pin. By default we support fan 1, so disable heater 6.
pids[heater]->Init(-1.0, -1.0, -1.0, true, false);
@@ -182,7 +182,7 @@ void Heat::Task()
lastWakeTime = xTaskGetTickCount();
for (;;)
{
- for (size_t heater = 0; heater < Heaters; heater++)
+ for (size_t heater = 0; heater < NumHeaters; heater++)
{
pids[heater]->Spin();
}
@@ -212,7 +212,7 @@ void Heat::Spin()
if (now - lastTime >= platform.HeatSampleInterval())
{
lastTime = now;
- for (size_t heater = 0; heater < Heaters; heater++)
+ for (size_t heater = 0; heater < NumHeaters; heater++)
{
pids[heater]->Spin();
}
@@ -273,7 +273,7 @@ bool Heat::AllHeatersAtSetTemperatures(bool includingBed) const
bool Heat::HeaterAtSetTemperature(int8_t heater, bool waitWhenCooling) const
{
// If it hasn't anything to do, it must be right wherever it is...
- if (heater < 0 || heater >= (int)Heaters || pids[heater]->SwitchedOff() || pids[heater]->FaultOccurred())
+ if (heater < 0 || heater >= (int)NumHeaters || pids[heater]->SwitchedOff() || pids[heater]->FaultOccurred())
{
return true;
}
@@ -287,7 +287,7 @@ bool Heat::HeaterAtSetTemperature(int8_t heater, bool waitWhenCooling) const
Heat::HeaterStatus Heat::GetStatus(int8_t heater) const
{
- if (heater < 0 || heater >= (int)Heaters)
+ if (heater < 0 || heater >= (int)NumHeaters)
{
return HS_off;
}
@@ -345,7 +345,7 @@ bool Heat::IsChamberHeater(int8_t heater) const
void Heat::SetActiveTemperature(int8_t heater, float t)
{
- if (heater >= 0 && heater < (int)Heaters)
+ if (heater >= 0 && heater < (int)NumHeaters)
{
pids[heater]->SetActiveTemperature(t);
}
@@ -353,12 +353,12 @@ void Heat::SetActiveTemperature(int8_t heater, float t)
float Heat::GetActiveTemperature(int8_t heater) const
{
- return (heater >= 0 && heater < (int)Heaters) ? pids[heater]->GetActiveTemperature() : ABS_ZERO;
+ return (heater >= 0 && heater < (int)NumHeaters) ? pids[heater]->GetActiveTemperature() : ABS_ZERO;
}
void Heat::SetStandbyTemperature(int8_t heater, float t)
{
- if (heater >= 0 && heater < (int)Heaters)
+ if (heater >= 0 && heater < (int)NumHeaters)
{
pids[heater]->SetStandbyTemperature(t);
}
@@ -366,13 +366,13 @@ void Heat::SetStandbyTemperature(int8_t heater, float t)
float Heat::GetStandbyTemperature(int8_t heater) const
{
- return (heater >= 0 && heater < (int)Heaters) ? pids[heater]->GetStandbyTemperature() : ABS_ZERO;
+ return (heater >= 0 && heater < (int)NumHeaters) ? pids[heater]->GetStandbyTemperature() : ABS_ZERO;
}
float Heat::GetHighestTemperatureLimit(int8_t heater) const
{
float limit = BAD_ERROR_TEMPERATURE;
- if (heater >= 0 && heater < (int)Heaters)
+ if (heater >= 0 && heater < (int)NumHeaters)
{
for (const HeaterProtection *prot : heaterProtections)
{
@@ -392,7 +392,7 @@ float Heat::GetHighestTemperatureLimit(int8_t heater) const
float Heat::GetLowestTemperatureLimit(int8_t heater) const
{
float limit = ABS_ZERO;
- if (heater >= 0 && heater < (int)Heaters)
+ if (heater >= 0 && heater < (int)NumHeaters)
{
for (const HeaterProtection *prot : heaterProtections)
{
@@ -412,7 +412,7 @@ float Heat::GetLowestTemperatureLimit(int8_t heater) const
// Get the current temperature of a heater
float Heat::GetTemperature(int8_t heater) const
{
- return (heater >= 0 && heater < (int)Heaters) ? pids[heater]->GetTemperature() : ABS_ZERO;
+ return (heater >= 0 && heater < (int)NumHeaters) ? pids[heater]->GetTemperature() : ABS_ZERO;
}
// Get the target temperature of a heater
@@ -426,7 +426,7 @@ float Heat::GetTargetTemperature(int8_t heater) const
void Heat::Activate(int8_t heater)
{
- if (heater >= 0 && heater < (int)Heaters)
+ if (heater >= 0 && heater < (int)NumHeaters)
{
pids[heater]->Activate();
}
@@ -434,7 +434,7 @@ void Heat::Activate(int8_t heater)
void Heat::SwitchOff(int8_t heater)
{
- if (heater >= 0 && heater < (int)Heaters)
+ if (heater >= 0 && heater < (int)NumHeaters)
{
pids[heater]->SwitchOff();
lastStandbyTools[heater] = nullptr;
@@ -443,7 +443,7 @@ void Heat::SwitchOff(int8_t heater)
void Heat::SwitchOffAll(bool includingChamberAndBed)
{
- for (int heater = 0; heater < (int)Heaters; ++heater)
+ for (int heater = 0; heater < (int)NumHeaters; ++heater)
{
if (includingChamberAndBed || !IsBedOrChamberHeater(heater))
{
@@ -454,7 +454,7 @@ void Heat::SwitchOffAll(bool includingChamberAndBed)
void Heat::Standby(int8_t heater, const Tool *tool)
{
- if (heater >= 0 && heater < (int)Heaters)
+ if (heater >= 0 && heater < (int)NumHeaters)
{
pids[heater]->Standby();
lastStandbyTools[heater] = tool;
@@ -463,7 +463,7 @@ void Heat::Standby(int8_t heater, const Tool *tool)
void Heat::ResetFault(int8_t heater)
{
- if (heater >= 0 && heater < (int)Heaters)
+ if (heater >= 0 && heater < (int)NumHeaters)
{
pids[heater]->ResetFault();
}
@@ -599,7 +599,7 @@ GCodeResult Heat::ConfigureHeaterSensor(unsigned int mcode, size_t heater, GCode
// Get a pointer to the temperature sensor entry, or nullptr if the heater number is bad
TemperatureSensor **Heat::GetSensor(size_t heater)
{
- if (heater < Heaters)
+ if (heater < NumHeaters)
{
return &heaterSensors[heater];
}
@@ -613,7 +613,7 @@ TemperatureSensor **Heat::GetSensor(size_t heater)
// Get a pointer to the temperature sensor entry, or nullptr if the heater number is bad (const version of above)
TemperatureSensor * const *Heat::GetSensor(size_t heater) const
{
- if (heater < Heaters)
+ if (heater < NumHeaters)
{
return &heaterSensors[heater];
}
@@ -636,7 +636,7 @@ HeaterProtection& Heat::AccessHeaterProtection(size_t index) const
{
if (index >= FirstExtraHeaterProtection && index < FirstExtraHeaterProtection + NumExtraHeaterProtections)
{
- return *heaterProtections[index + Heaters - FirstExtraHeaterProtection];
+ return *heaterProtections[index + NumHeaters - FirstExtraHeaterProtection];
}
return *heaterProtections[index];
}
diff --git a/src/Heating/Heat.h b/src/Heating/Heat.h
index 941db7c7..c139f4a6 100644
--- a/src/Heating/Heat.h
+++ b/src/Heating/Heat.h
@@ -60,13 +60,13 @@ public:
int8_t GetBedHeater(size_t index) const // Get a hot bed heater number
pre(index < NumBedHeaters);
void SetBedHeater(size_t index, int8_t heater) // Set a hot bed heater number
- pre(index < NumBedHeaters; -1 <= heater; heater < Heaters);
+ pre(index < NumBedHeaters; -1 <= heater; heater < NumHeaters);
bool IsBedHeater(int8_t heater) const; // Check if this heater is a bed heater
int8_t GetChamberHeater(size_t index) const // Get a chamber heater number
pre(index < NumChamberHeaters);
void SetChamberHeater(size_t index, int8_t heater) // Set a chamber heater number
- pre(index < NumChamberHeaters; -1 <= heater; heater < Heaters);
+ pre(index < NumChamberHeaters; -1 <= heater; heater < NumHeaters);
bool IsChamberHeater(int8_t heater) const; // Check if this heater is a chamber heater
void SetActiveTemperature(int8_t heater, float t);
@@ -88,46 +88,46 @@ public:
void Diagnostics(MessageType mtype); // Output useful information
float GetAveragePWM(size_t heater) const // Return the running average PWM to the heater as a fraction in [0, 1].
- pre(heater < Heaters);
+ pre(heater < NumHeaters);
- bool IsBedOrChamberHeater(int8_t heater) const; // Queried by the Platform class
+ bool IsBedOrChamberHeater(int8_t heater) const; // Queried by the Platform class
uint32_t GetLastSampleTime(size_t heater) const
- pre(heater < Heaters);
+ pre(heater < NumHeaters);
void StartAutoTune(size_t heater, float temperature, float maxPwm, const StringRef& reply) // Auto tune a PID
- pre(heater < Heaters);
+ pre(heater < NumHeaters);
bool IsTuning(size_t heater) const // Return true if the specified heater is auto tuning
- pre(heater < Heaters);
+ pre(heater < NumHeaters);
void GetAutoTuneStatus(const StringRef& reply) const; // Get the status of the current or last auto tune
const FopDt& GetHeaterModel(size_t heater) const // Get the process model for the specified heater
- pre(heater < Heaters);
+ pre(heater < NumHeaters);
bool SetHeaterModel(size_t heater, float gain, float tc, float td, float maxPwm, float voltage, bool usePid, bool inverted, PwmFrequency pwmFreq) // Set the heater process model
- pre(heater < Heaters);
+ pre(heater < NumHeaters);
bool IsHeaterSignalInverted(size_t heater) // Set PWM signal inversion
- pre(heater < Heaters);
+ pre(heater < NumHeaters);
void SetHeaterSignalInverted(size_t heater, bool IsInverted) // Set PWM signal inversion
- pre(heater < Heaters);
+ pre(heater < NumHeaters);
void GetFaultDetectionParameters(size_t heater, float& maxTempExcursion, float& maxFaultTime) const
- pre(heater < Heaters);
+ pre(heater < NumHeaters);
void SetFaultDetectionParameters(size_t heater, float maxTempExcursion, float maxFaultTime)
- pre(heater < Heaters);
+ pre(heater < NumHeaters);
bool IsHeaterEnabled(size_t heater) const // Is this heater enabled?
- pre(heater < Heaters);
+ pre(heater < NumHeaters);
float GetHighestTemperatureLimit() const; // Get the highest temperature limit of any heater
void SetM301PidParameters(size_t heater, const M301PidParameters& params)
- pre(heater < Heaters);
+ pre(heater < NumHeaters);
bool WriteModelParameters(FileStore *f) const; // Write heater model parameters to file returning true if no error
@@ -140,12 +140,12 @@ public:
void UpdateHeaterProtection(); // Updates the PIDs and HeaterProtection items when a heater is remapped
bool CheckHeater(size_t heater) // Check if the heater is able to operate
- pre(heater < Heaters);
+ pre(heater < NumHeaters);
float GetTemperature(size_t heater, TemperatureError& err); // Result is in degrees Celsius
const Tool* GetLastStandbyTool(int heater) const
- pre(heater >= 0; heater < Heaters)
+ pre(heater >= 0; heater < NumHeaters)
{
return lastStandbyTools[heater];
}
@@ -162,12 +162,12 @@ private:
Platform& platform; // The instance of the RepRap hardware class
- HeaterProtection *heaterProtections[Heaters + NumExtraHeaterProtections]; // Heater protection instances to guarantee legal heater temperature ranges
+ HeaterProtection *heaterProtections[NumHeaters + NumExtraHeaterProtections]; // Heater protection instances to guarantee legal heater temperature ranges
- PID* pids[Heaters]; // A PID controller for each heater
- const Tool* lastStandbyTools[Heaters]; // The last tool that caused the corresponding heater to be set to standby
+ PID* pids[NumHeaters]; // A PID controller for each heater
+ const Tool* lastStandbyTools[NumHeaters]; // The last tool that caused the corresponding heater to be set to standby
- TemperatureSensor *heaterSensors[Heaters]; // The sensor used by the real heaters
+ TemperatureSensor *heaterSensors[NumHeaters]; // The sensor used by the real heaters
TemperatureSensor *virtualHeaterSensors[MaxVirtualHeaters]; // Sensors for virtual heaters
#ifdef RTOS
diff --git a/src/Heating/HeaterProtection.cpp b/src/Heating/HeaterProtection.cpp
index e8d4a9a5..fe94a933 100644
--- a/src/Heating/HeaterProtection.cpp
+++ b/src/Heating/HeaterProtection.cpp
@@ -16,7 +16,7 @@ HeaterProtection::HeaterProtection(size_t index) : next(nullptr)
{
// By default each heater protection element is mapped to its corresponding heater.
// All other heater protection elements are unused and can be optionally assigned.
- heater = supervisedHeater = (index >= Heaters) ? -1 : (int8_t)index;
+ heater = supervisedHeater = (index >= NumHeaters) ? -1 : (int8_t)index;
}
void HeaterProtection::Init(float tempLimit)
diff --git a/src/Heating/Pid.cpp b/src/Heating/Pid.cpp
index 1472583f..152bdd40 100644
--- a/src/Heating/Pid.cpp
+++ b/src/Heating/Pid.cpp
@@ -86,7 +86,7 @@ bool PID::SetModel(float gain, float tc, float td, float maxPwm, float voltage,
if (rslt)
{
#if defined(DUET_06_085)
- if (heater == Heaters - 1)
+ if (heater == NumHeaters - 1)
{
// The last heater on the Duet 0.8.5 + DueX4 shares its pin with Fan1
platform.EnableSharedFan(!model.IsEnabled());
diff --git a/src/Movement/Move.cpp b/src/Movement/Move.cpp
index 37d5a771..ddb7a462 100644
--- a/src/Movement/Move.cpp
+++ b/src/Movement/Move.cpp
@@ -518,10 +518,10 @@ bool Move::PausePrint(RestorePoint& rp)
return true;
}
-#if HAS_VOLTAGE_MONITOR
+#if HAS_VOLTAGE_MONITOR || HAS_STALL_DETECT
// Pause the print immediately, returning true if we were able to skip or abort any moves and setting up to the move we aborted
-bool Move::LowPowerPause(RestorePoint& rp)
+bool Move::LowPowerOrStallPause(RestorePoint& rp)
{
const DDA * const savedDdaRingAddPointer = ddaRingAddPointer;
bool abortedMove = false;
diff --git a/src/Movement/Move.h b/src/Movement/Move.h
index 87070b4b..504693aa 100644
--- a/src/Movement/Move.h
+++ b/src/Movement/Move.h
@@ -112,8 +112,8 @@ public:
void PrintCurrentDda() const; // For debugging
bool PausePrint(RestorePoint& rp); // Pause the print as soon as we can, returning true if we were able to
-#if HAS_VOLTAGE_MONITOR
- bool LowPowerPause(RestorePoint& rp); // Pause the print immediately, returning true if we were able to
+#if HAS_VOLTAGE_MONITOR || HAS_STALL_DETECT
+ bool LowPowerOrStallPause(RestorePoint& rp); // Pause the print immediately, returning true if we were able to
#endif
bool NoLiveMovement() const; // Is a move running, or are there any queued?
diff --git a/src/Movement/StepperDrivers/TMC22xx.cpp b/src/Movement/StepperDrivers/TMC22xx.cpp
index 68ec86f8..0515be81 100644
--- a/src/Movement/StepperDrivers/TMC22xx.cpp
+++ b/src/Movement/StepperDrivers/TMC22xx.cpp
@@ -1,5 +1,5 @@
/*
- * TMC2660.cpp
+ * TMC22xx.cpp
*
* Created on: 23 Jan 2016
* Author: David
@@ -36,8 +36,6 @@ enum class DriversState : uint8_t
static DriversState driversState = DriversState::noPower;
-const int ChopperControlRegisterMode = 999; // mode passed to get/set microstepping to indicate we want the chopper control register
-
// GCONF register (0x00, RW)
constexpr uint8_t REGNUM_GCONF = 0x00;
constexpr uint32_t GCONF_USE_VREF = 1 << 0; // use external VRef
diff --git a/src/Movement/StepperDrivers/TMC22xx.h b/src/Movement/StepperDrivers/TMC22xx.h
index d3f2d627..7aed6ca2 100644
--- a/src/Movement/StepperDrivers/TMC22xx.h
+++ b/src/Movement/StepperDrivers/TMC22xx.h
@@ -1,5 +1,5 @@
/*
- * ExternalDrivers.h
+ * TMC22xx.h
*
* Created on: 23 Jan 2016
* Author: David
diff --git a/src/Movement/StepperDrivers/TMC2660.cpp b/src/Movement/StepperDrivers/TMC2660.cpp
index 9405847a..4c439f9e 100644
--- a/src/Movement/StepperDrivers/TMC2660.cpp
+++ b/src/Movement/StepperDrivers/TMC2660.cpp
@@ -12,7 +12,13 @@
#include "TMC2660.h"
#include "RepRap.h"
#include "Movement/Move.h"
-#include "sam/drivers/pdc/pdc.h"
+
+# if SAME70
+# include "sam/drivers/xdmac/xdmac.h"
+# else
+# include "sam/drivers/pdc/pdc.h"
+# endif
+
#include "sam/drivers/usart/usart.h"
const float MaximumMotorCurrent = 2400.0;
@@ -26,8 +32,6 @@ static size_t numTmc2660Drivers;
static bool driversPowered = false;
-const int ChopperControlRegisterMode = 999; // mode passed to get/set microstepping to indicate we want the chopper control register
-
// The SPI clock speed is a compromise:
// - too high and polling the driver chips take too much of the CPU time
// - too low and we won't detect stalls quickly enough
@@ -227,12 +231,14 @@ private:
// State structures for all drivers
static TmcDriverState driverStates[MaxSmartDrivers];
+#if !SAME70
// PDC address
static Pdc * const spiPdc =
-#if TMC2660_USES_USART
+# if TMC2660_USES_USART
usart_get_pdc_base(USART_TMC2660);
-#else
+# else
spi_get_pdc_base(SPI_TMC2660);
+# endif
#endif
// Words to send and receive driver SPI data from/to
@@ -245,6 +251,97 @@ static TmcDriverState * volatile currentDriver = nullptr; // volatile because th
// Set up the PDC to send a register and receive the status
/*static*/ inline void TmcDriverState::SetupDMA(uint32_t outVal)
{
+#if SAME70
+ /* From the data sheet:
+ * Single Block Transfer With Single Microblock
+ 1. Read the XDMAC Global Channel Status Register (XDMAC_GS) to select a free channel. [we use fixed channel numbers instead.]
+ 2. Clear the pending Interrupt Status bit(s) by reading the selected XDMAC Channel x Interrupt Status
+ Register (XDMAC_CISx).
+ 3. Write the XDMAC Channel x Source Address Register (XDMAC_CSAx) for channel x.
+ 4. Write the XDMAC Channel x Destination Address Register (XDMAC_CDAx) for channel x.
+ 5. Program field UBLEN in the XDMAC Channel x Microblock Control Register (XDMAC_CUBCx) with
+ the number of data.
+ 6. Program the XDMAC Channel x Configuration Register (XDMAC_CCx):
+ 6.1. Clear XDMAC_CCx.TYPE for a memory-to-memory transfer, otherwise set this bit.
+ 6.2. Configure XDMAC_CCx.MBSIZE to the memory burst size used.
+ 6.3. Configure XDMAC_CCx.SAM and DAM to Memory Addressing mode.
+ 6.4. Configure XDMAC_CCx.DSYNC to select the peripheral transfer direction.
+ 6.5. Configure XDMAC_CCx.CSIZE to configure the channel chunk size (only relevant for
+ peripheral synchronized transfer).
+ 6.6. Configure XDMAC_CCx.DWIDTH to configure the transfer data width.
+ 6.7. Configure XDMAC_CCx.SIF, XDMAC_CCx.DIF to configure the master interface used to
+ read data and write data, respectively.
+ 6.8. Configure XDMAC_CCx.PERID to select the active hardware request line (only relevant for
+ a peripheral synchronized transfer).
+ 6.9. Set XDMAC_CCx.SWREQ to use a software request (only relevant for a peripheral
+ synchronized transfer).
+ 7. Clear the following five registers:
+ – XDMAC Channel x Next Descriptor Control Register (XDMAC_CNDCx)
+ – XDMAC Channel x Block Control Register (XDMAC_CBCx)
+ – XDMAC Channel x Data Stride Memory Set Pattern Register (XDMAC_CDS_MSPx)
+ – XDMAC Channel x Source Microblock Stride Register (XDMAC_CSUSx)
+ – XDMAC Channel x Destination Microblock Stride Register (XDMAC_CDUSx)
+ This indicates that the linked list is disabled, there is only one block and striding is disabled.
+ 8. Enable the Microblock interrupt by writing a ‘1’ to bit BIE in the XDMAC Channel x Interrupt Enable
+ Register (XDMAC_CIEx). Enable the Channel x Interrupt Enable bit by writing a ‘1’ to bit IEx in the
+ XDMAC Global Interrupt Enable Register (XDMAC_GIE).
+ 9. Enable channel x by writing a ‘1’ to bit ENx in the XDMAC Global Channel Enable Register
+ (XDMAC_GE). XDMAC_GS.STx (XDMAC Channel x Status bit) is set by hardware.
+ 10. Once completed, the DMA channel sets XDMAC_CISx.BIS (End of Block Interrupt Status bit) and
+ generates an interrupt. XDMAC_GS.STx is cleared by hardware. The software can either wait for
+ an interrupt or poll the channel status bit.
+
+ The following code is adapted form the code in the HSMCI driver.
+ */
+
+ // Receive
+ {
+ xdmac_channel_disable(XDMAC, XDMAC_CHAN_TMC_RX);
+ xdmac_channel_config_t p_cfg = {0, 0, 0, 0, 0, 0, 0, 0};
+ p_cfg.mbr_cfg = XDMAC_CC_TYPE_PER_TRAN
+ | XDMAC_CC_MBSIZE_SINGLE
+ | XDMAC_CC_DSYNC_PER2MEM
+ | XDMAC_CC_CSIZE_CHK_1
+ | XDMAC_CC_DWIDTH_BYTE
+ | XDMAC_CC_SIF_AHB_IF1
+ | XDMAC_CC_DIF_AHB_IF0
+ | XDMAC_CC_SAM_FIXED_AM
+ | XDMAC_CC_DAM_INCREMENTED_AM
+ | XDMAC_CC_PERID(XDMAC_CHAN_TMC_RX);
+ p_cfg.mbr_ubc = 3;
+ HSMCI->HSMCI_MR |= HSMCI_MR_FBYTE;
+ p_cfg.mbr_sa = reinterpret_cast<uint32_t>(&(USART_TMC2660->US_RHR));
+ p_cfg.mbr_da = reinterpret_cast<uint32_t>(&spiDataIn);
+ xdmac_configure_transfer(XDMAC, XDMAC_CHAN_TMC_RX, &p_cfg);
+ }
+
+ // Transmit
+ {
+ xdmac_channel_disable(XDMAC, XDMAC_CHAN_TMC_TX);
+ xdmac_channel_config_t p_cfg = {0, 0, 0, 0, 0, 0, 0, 0};
+ p_cfg.mbr_cfg = XDMAC_CC_TYPE_PER_TRAN
+ | XDMAC_CC_MBSIZE_SINGLE
+ | XDMAC_CC_DSYNC_MEM2PER
+ | XDMAC_CC_CSIZE_CHK_1
+ | XDMAC_CC_DWIDTH_BYTE
+ | XDMAC_CC_SIF_AHB_IF0
+ | XDMAC_CC_DIF_AHB_IF1
+ | XDMAC_CC_SAM_INCREMENTED_AM
+ | XDMAC_CC_DAM_FIXED_AM
+ | XDMAC_CC_PERID(XDMAC_CHAN_TMC_TX);
+ p_cfg.mbr_ubc = 3;
+ HSMCI->HSMCI_MR |= HSMCI_MR_FBYTE;
+ p_cfg.mbr_sa = reinterpret_cast<uint32_t>(&spiDataOut);
+ p_cfg.mbr_da = reinterpret_cast<uint32_t>(&(USART_TMC2660->US_THR));
+ xdmac_configure_transfer(XDMAC, XDMAC_CHAN_TMC_TX, &p_cfg);
+ }
+
+ // SPI sends data MSB first, but the firmware uses little-endian mode, so we need to reverse the byte order
+ spiDataOut = cpu_to_be32(outVal << 8);
+
+ xdmac_channel_enable(XDMAC, XDMAC_CHAN_TMC_RX);
+ xdmac_channel_enable(XDMAC, XDMAC_CHAN_TMC_TX);
+#else
// Faster code, not using the ASF
spiPdc->PERIPH_PTCR = (PERIPH_PTCR_RXTDIS | PERIPH_PTCR_TXTDIS); // disable the PDC
@@ -258,6 +355,7 @@ static TmcDriverState * volatile currentDriver = nullptr; // volatile because th
spiPdc->PERIPH_RCR = 3;
spiPdc->PERIPH_PTCR = (PERIPH_PTCR_RXTEN | PERIPH_PTCR_TXTEN); // enable the PDC
+#endif
}
// Initialise the state of the driver and its CS pin
@@ -591,13 +689,21 @@ inline void TmcDriverState::StartTransfer()
#endif
fastDigitalWriteLow(pin); // set CS low
- SetupDMA(regVal); // set up the PDC
+ SetupDMA(regVal); // set up the PDC or DMAC
-#if TMC2660_USES_USART
+ // Enable the interrupt
+#if SAME70
+ xdmac_channel_enable_interrupt(XDMAC, XDMAC_CHAN_TMC_RX, XDMAC_CIE_BIE);
+#elif TMC2660_USES_USART
USART_TMC2660->US_IER = US_IER_ENDRX; // enable end-of-transfer interrupt
- USART_TMC2660->US_CR = US_CR_RXEN | US_CR_TXEN; // enable transmitter and receiver
#else
SPI_TMC2660->SPI_IER = SPI_IER_ENDRX; // enable end-of-transfer interrupt
+#endif
+
+ // Enable the transfer
+#if TMC2660_USES_USART
+ USART_TMC2660->US_CR = US_CR_RXEN | US_CR_TXEN; // enable transmitter and receiver
+#else
SPI_TMC2660->SPI_CR = SPI_CR_SPIEN; // enable SPI
#endif
@@ -633,7 +739,9 @@ void TMC2660_SPI_Handler(void)
// Driver power is down or there is no current driver, so stop polling
-#if TMC2660_USES_USART
+#if SAME70
+ xdmac_channel_disable_interrupt(XDMAC, XDMAC_CHAN_TMC_RX, XDMAC_CIE_BIE);
+#elif TMC2660_USES_USART
USART_TMC2660->US_IDR = US_IDR_ENDRX;
#else
SPI_TMC2660->SPI_IDR = SPI_IDR_ENDRX;
@@ -702,6 +810,13 @@ namespace SmartDrivers
{
driverStates[driver].Init(driver, driverSelectPins[driver]); // axes are mapped straight through to drivers initially
}
+
+#if SAME70
+ pmc_enable_periph_clk(ID_XDMAC);
+ xdmac_channel_disable_interrupt(XDMAC, XDMAC_CHAN_TMC_TX, 0xFFFFFFFF);
+ xdmac_channel_disable_interrupt(XDMAC, XDMAC_CHAN_TMC_RX, 0xFFFFFFFF);
+ xdmac_enable_interrupt(XDMAC, XDMAC_CHAN_TMC_RX);
+#endif
}
void SetAxisNumber(size_t driver, uint32_t axisNumber)
diff --git a/src/Movement/StepperDrivers/TMC2660.h b/src/Movement/StepperDrivers/TMC2660.h
index a659cc7b..a94aedcb 100644
--- a/src/Movement/StepperDrivers/TMC2660.h
+++ b/src/Movement/StepperDrivers/TMC2660.h
@@ -1,5 +1,5 @@
/*
- * ExternalDrivers.h
+ * TMC2660.h
*
* Created on: 23 Jan 2016
* Author: David
diff --git a/src/Movement/StepperDrivers/TMC51xx.cpp b/src/Movement/StepperDrivers/TMC51xx.cpp
new file mode 100644
index 00000000..2c5efd18
--- /dev/null
+++ b/src/Movement/StepperDrivers/TMC51xx.cpp
@@ -0,0 +1,617 @@
+/*
+ * TMC51xx.cpp
+ *
+ * Created on: 26 Aug 2018
+ * Author: David
+ * Purpose:
+ * Support for TMC5130 and TMC5160 stepper drivers
+ */
+
+#include "RepRapFirmware.h"
+
+#if SUPPORT_TMC51xx
+
+#include "TMC51xx.h"
+
+// The SPI clock speed is a compromise:
+// - too high and polling the driver chips take too much of the CPU time
+// - too low and we won't detect stalls quickly enough
+// With a 4MHz SPI clock:
+// - polling the drivers makes calculations take ??% longer, so it is taking about ??% of the CPU time
+// - we poll all ?? drivers in about ??us
+// With a 2MHz SPI clock:
+// - polling the drivers makes calculations take ??% longer, so it is taking about ??% of the CPU time
+// - we poll all ?? drivers in about ??us
+const uint32_t DriversSpiClockFrequency = 2000000; // 2MHz SPI clock
+const uint32_t TransferTimeout = 2; // any transfer should complete within 2 ticks @ 1ms/tick
+
+// GCONF register (0x00, RW)
+constexpr uint8_t REGNUM_GCONF = 0x00;
+
+constexpr uint32_t GCONF_5130_USE_VREF = 1 << 0; // use external VRef
+constexpr uint32_t GCONF_5130_INT_RSENSE = 1 << 1; // use internal sense resistors
+constexpr uint32_t GCONF_5130_END_COMMUTATION = 1 << 3; // Enable commutation by full step encoder (DCIN_CFG5 = ENC_A, DCEN_CFG4 = ENC_B)
+
+constexpr uint32_t GCONF_5160_RECAL = 1 << 0; // Zero crossing recalibration during driver disable (via ENN or via TOFF setting)
+constexpr uint32_t GCONF_5160_FASTSTANDSTILL = 1 << 1; // Timeout for step execution until standstill detection: 1: Short time: 2^18 clocks, 0: Normal time: 2^20 clocks
+constexpr uint32_t GCONF_5160_MULTISTEP_FILT = 1 << 3; // Enable step input filtering for stealthChop optimization with external step source (default=1)
+
+constexpr uint32_t GCONF_SPREAD_CYCLE = 1 << 2; // use spread cycle mode (else stealthchop mode)
+constexpr uint32_t GCONF_REV_DIR = 1 << 4; // reverse motor direction
+constexpr uint32_t GCONF_DIAG0_ERROR = 1 << 5; // Enable DIAG0 active on driver errors: Over temperature (ot), short to GND (s2g), undervoltage chargepump (uv_cp)
+ // DIAG0 always shows the reset-status, i.e. is active low during reset condition.
+constexpr uint32_t GCONF_DIAG0_OTPW = 1 << 6; // Enable DIAG0 active on driver over temperature prewarning (otpw)
+constexpr uint32_t GCONF_DIAG0_STALL = 1 << 7; // Enable DIAG0 active on motor stall (set TCOOLTHRS before using this feature)
+constexpr uint32_t GCONF_DIAG1_STALL = 1 << 8; // Enable DIAG1 active on motor stall (set TCOOLTHRS before using this feature)
+constexpr uint32_t GCONF_DIAG1_INDEX = 1 << 9; // Enable DIAG1 active on index position (microstep look up table position 0)
+constexpr uint32_t GCONF_DIAG1_ONSTATE = 1 << 10; // Enable DIAG1 active when chopper is on (for the coil which is in the second half of the fullstep)
+constexpr uint32_t GCONF_DIAG1_STEPS_SKIPPED = 1 << 11; // Enable output toggle when steps are skipped in dcStep mode (increment of LOST_STEPS). Do not enable in conjunction with other DIAG1 options.
+constexpr uint32_t GCONF_DIAG0_PUSHPULL = 1 << 12; // 0: SWN_DIAG0 is open collector output (active low), 1: Enable SWN_DIAG0 push pull output (active high)
+constexpr uint32_t GCONF_DIAG1_PUSHPULL = 1 << 13; // 0: SWN_DIAG1 is open collector output (active low), 1: Enable SWN_DIAG1 push pull output (active high)
+constexpr uint32_t GCONF_SMALL_HYSTERESIS = 1 << 14; // 0: Hysteresis for step frequency comparison is 1/16, 1: Hysteresis for step frequency comparison is 1/32
+constexpr uint32_t GCONF_STOP_ENABLE = 1 << 15; // 0: Normal operation, 1: Emergency stop: ENCA_DCIN stops the sequencer when tied high (no steps become executed by the sequencer, motor goes to standstill state)
+constexpr uint32_t GCONF_DIRECT_MODE = 1 << 16; // 0: Normal operation, 1: Motor coil currents and polarity directly programmed via serial interface:
+ // Register XTARGET (0x2D) specifies signed coil A current (bits 8..0) and coil B current (bits 24..16).
+ // In this mode, the current is scaled by IHOLD setting. Velocity based current regulation of stealthChop
+ // is not available in this mode. The automatic stealthChop current regulation will work only for low stepper motor velocities.
+constexpr uint32_t GCONF_TEST_MODE = 1 << 17; // 0: Normal operation, 1: Enable analog test output on pin ENCN_DCO. IHOLD[1..0] selects the function of ENCN_DCO: 0…2: T120, DAC, VDDH
+
+constexpr uint32_t DefaultGConfReg_5130 = 0;
+constexpr uint32_t DefaultGConfReg_5160 = GCONF_5160_MULTISTEP_FILT;
+
+// General configuration and status registers
+
+// GSTAT register (0x01, RW). Write 1 bits to clear the flags.
+constexpr uint8_t REGNUM_GSTAT = 0x01;
+constexpr uint32_t GSTAT_RESET = 1 << 0; // driver has been reset since last read
+constexpr uint32_t GSTAT_DRV_ERR = 1 << 1; // driver has been shut down due to over temp or short circuit
+constexpr uint32_t GSTAT_UV_CP = 1 << 2; // undervoltage on charge pump, driver disabled. Not latched so does not need to be cleared.
+
+// IFCOUNT register (0x02, RO) is not used in SPI mode
+// SLAVECONF register (0x03, WO) is not used in SPI mode
+// IOIN register (0x04, RO) reads the state of all input pins. We don't use it.
+// OUTPUT register (0x04, WO) is not used in SPI mode
+// X_COMPARE register (0x05, WO) allows us to get a pulse on DIAG1 when an index is passed. We don't use it.
+// OTP_PROG register (0x06, WO, 5160 only) is not used in this firmware
+// OTP_READ register (0x07, RO, 5160 only) is not used in this firmware
+// FACTORY_CONF register (0x08, RW, 5160 only) trims the clock frequency and is preset for 12MHz
+
+// SHORT_CONF register
+constexpr uint8_t REGNUM_5160_SHORTCONF = 0x09;
+
+constexpr uint32_t SHORTCONF_S2VS_LEVEL_SHIFT = 0;
+constexpr uint32_t SHORTCONF_S2VS_LEVEL_MASK = 15; // Short to VS detector level for lowside FETs. Checks for voltage drop in LS MOSFET and sense resistor.
+ // 4 (highest sensitivity) … 15 (lowest sensitivity); 10 recommended for normal operation (Reset default 12 via OTP)
+ // Hint: Settings from 1 to 3 will trigger during normal operation due to voltage drop on sense resistor.
+constexpr uint32_t SHORTCONF_S2G_LEVEL_SHIFT = 8;
+constexpr uint32_t SHORTCONF_S2G_LEVEL_MASK = (15 << 8); // Short to GND detector level for highside FETs. Checks for voltage drop on high side MOSFET
+ // 2 (highest sensitivity) … 15 (lowest sensitivity) 6 to 10 recommended (Reset Default: 12 via OTP)
+constexpr uint32_t SHORTCONF_FILTER_SHIFT = 16;
+constexpr uint32_t SHORTCONF_FILTER_MASK = (3 << 16); // Spike filtering bandwidth for short detection 0 (lowest, 100ns), 1 (1us), 2 (2us) 3 (3us)
+ // Hint: A good PCB layout will allow using setting 0. Increase value, if erroneous short detection occurs. Reset Default = 1
+constexpr uint32_t SHORTCONF_DELAY = (1 << 18); // Short detection delay 0=750ns: normal, 1=1500ns: high The short detection delay shall cover the bridge switching time.
+ // 0 will work for most applications. (Reset Default = 0)
+
+// DRV_CONF register
+constexpr uint8_t REGNUM_5160_DRVCONF = 0x0A;
+constexpr uint32_t DRVCONF_BBMTIME_SHIFT = 0;
+constexpr uint32_t DRVCONF_BBMTIME_MASK = 31; // Break-Before make delay 0=shortest (100ns) … 16 (200ns) … 24=longest (375ns) >24 not recommended, use BBMCLKS instead
+ // Hint: 0 recommended due to fast switching MOSFETs (Reset Default = 0)
+constexpr uint32_t DRVCONF_BBMCLKS_SHIFT = 8;
+constexpr uint32_t DRVCONF_BBMCLKS_MASK = (15 << 8); // Digital BBM time in clock cycles (typ. 83ns). The longer setting rules (BBMTIME vs. BBMCLKS).
+ // Reset Default: 2 via OTP. Hint: 2, or down to 0 recommended due to fast switching MOSFETs
+constexpr uint32_t DRVCONF_OTSELECT_SHIFT = 16;
+constexpr uint32_t DRVCONF_OTSELECT_MASK = (3 << 16); // Selection of over temperature level for bridge disable, switch on after cool down to 120°C / OTPW level. Reset Default = 0.
+ // 00: 150°C (not recommended – MOSFET might overheat); 01: 143°C 10: 136°C (Recommended); 11: 120°C (not recommended, no hysteresis)
+ // Hint: Adapt overtemperature threshold as required to protect the MOSFETs or other components on the PCB.
+constexpr uint32_t DRVCONF_STRENGTH_SHIFT = 18;
+constexpr uint32_t DRVCONF_STRENGTH_MASK = (3 << 18); // Selection of gate driver current. Adapts the gate driver current to the gate charge of the external MOSFETs.
+ // 00: Normal slope (Recommended) 01: Normal+TC (medium above OTPW level) 10: Fast slope. Reset Default = 10.
+constexpr uint32_t DRVCONF_FILT_ISENSE_SHIFT = 20;
+constexpr uint32_t DRVCONF_FILT_ISENSE_MASK = (3 << 20); // Filter time constant of sense amplifier to suppress ringing and coupling from second coil operation
+ // 00: low – 100ns 01: – 200ns 10: – 300ns 11: high – 400ns
+ // Hint: Increase setting if motor chopper noise occurs due to cross-coupling of both coils. Reset Default = 0.
+
+constexpr uint8_t REGNUM_5160_GLOBAL_SCALER = 0x0B; // Global scaling of Motor current. This value is multiplied to the current scaling in order to adapt a drive to a
+ // certain motor type. This value should be chosen before tuning other settings, because it also influences chopper hysteresis.
+ // 0: Full Scale (or write 256) 1 … 31: Not allowed for operation 32 … 255: 32/256 … 255/256 of maximum current.
+ // Hint: Values >128 recommended for best results. Reset Default 0.
+
+constexpr uint8_t REGNUM_5160_OFFSET_READ = 0x0B; // Bits 8..15: Offset calibration result phase A (signed). Bits 0..7: Offset calibration result phase B (signed).
+
+// Velocity dependent control registers
+
+// IHOLD_IRUN register (WO)
+constexpr uint8_t REGNUM_IHOLDIRUN = 0x10;
+constexpr uint32_t IHOLDIRUN_IHOLD_SHIFT = 0; // standstill current
+constexpr uint32_t IHOLDIRUN_IHOLD_MASK = 0x1F << IHOLDIRUN_IHOLD_SHIFT;
+constexpr uint32_t IHOLDIRUN_IRUN_SHIFT = 8;
+constexpr uint32_t IHOLDIRUN_IRUN_MASK = 0x1F << IHOLDIRUN_IRUN_SHIFT;
+constexpr uint32_t IHOLDIRUN_IHOLDDELAY_SHIFT = 16;
+constexpr uint32_t IHOLDIRUN_IHOLDDELAY_MASK = 0x0F << IHOLDIRUN_IHOLDDELAY_SHIFT;
+
+constexpr uint32_t DefaultIholdIrunReg = (0 << IHOLDIRUN_IHOLD_SHIFT) | (0 << IHOLDIRUN_IRUN_SHIFT) | (2 << IHOLDIRUN_IHOLDDELAY_SHIFT);
+ // approx. 0.5 sec motor current reduction to half power
+
+constexpr uint8_t REGNUM_TPOWER_DOWN = 0x11;
+constexpr uint8_t REGNUM_TSTEP = 0x12;
+constexpr uint8_t REGNUM_TPWMTHRS = 0x13;
+constexpr uint8_t REGNUM_VACTUAL = 0x22;
+
+// Sequencer registers (read only)
+constexpr uint8_t REGNUM_MSCNT = 0x6A;
+constexpr uint8_t REGNUM_MSCURACT = 0x6B;
+
+// Chopper control registers
+
+// CHOPCONF register
+constexpr uint8_t REGNUM_CHOPCONF = 0x6C;
+constexpr uint32_t CHOPCONF_TOFF_SHIFT = 0; // off time setting, 0 = disable driver
+constexpr uint32_t CHOPCONF_TOFF_MASK = 0x0F << CHOPCONF_TOFF_SHIFT;
+constexpr uint32_t CHOPCONF_HSTRT_SHIFT = 4; // hysteresis start
+constexpr uint32_t CHOPCONF_HSTRT_MASK = 0x07 << CHOPCONF_HSTRT_SHIFT;
+constexpr uint32_t CHOPCONF_HEND_SHIFT = 7; // hysteresis end
+constexpr uint32_t CHOPCONF_HEND_MASK = 0x0F << CHOPCONF_HEND_SHIFT;
+constexpr uint32_t CHOPCONF_TBL_SHIFT = 15; // blanking time
+constexpr uint32_t CHOPCONF_TBL_MASK = 0x03 << CHOPCONF_TBL_SHIFT;
+constexpr uint32_t CHOPCONF_VSENSE_HIGH = 1 << 17; // use high sensitivity current scaling
+constexpr uint32_t CHOPCONF_MRES_SHIFT = 24; // microstep resolution
+constexpr uint32_t CHOPCONF_MRES_MASK = 0x0F << CHOPCONF_MRES_SHIFT;
+constexpr uint32_t CHOPCONF_INTPOL = 1 << 28; // use interpolation
+constexpr uint32_t CHOPCONF_DEDGE = 1 << 29; // step on both edges
+constexpr uint32_t CHOPCONF_DISS2G = 1 << 30; // disable short to ground protection
+constexpr uint32_t CHOPCONF_DISS2VS = 1 << 31; // disable low side short protection
+
+constexpr uint32_t DefaultChopConfReg = 0x10000053 | CHOPCONF_VSENSE_HIGH; // this is the reset default + CHOPCONF_VSENSE_HIGH - try it until we find something better
+
+// DRV_STATUS register. See the .h file for the bit definitions.
+constexpr uint8_t REGNUM_DRV_STATUS = 0x6F;
+
+// PWMCONF register
+constexpr uint8_t REGNUM_PWMCONF = 0x70;
+
+constexpr uint32_t DefaultPwmConfReg = 0xC10D0024; // this is the reset default - try it until we find something better
+
+constexpr uint8_t REGNUM_PWM_SCALE = 0x71;
+constexpr uint8_t REGNUM_PWM_AUTO = 0x72;
+
+// Common data
+static size_t numTmc51xxDrivers;
+
+enum class DriversState : uint8_t
+{
+ noPower = 0,
+ initialising,
+ ready
+};
+
+static DriversState driversState = DriversState::noPower;
+
+//----------------------------------------------------------------------------------------------------------------------------------
+// Private types and methods
+
+class TmcDriverState
+{
+public:
+ void Init(uint32_t p_driverNumber, Pin p_pin);
+ void SetAxisNumber(size_t p_axisNumber);
+ void WriteAll();
+ bool SetChopConf(uint32_t newVal);
+ bool SetOffTime(uint32_t newVal);
+ uint32_t GetChopConf() const;
+ uint32_t GetOffTime() const;
+ void SetCoolStep(uint16_t coolStepConfig);
+ bool SetMicrostepping(uint32_t shift, bool interpolate);
+ unsigned int GetMicrostepping(bool& interpolation) const; // Get microstepping
+ bool SetDriverMode(unsigned int mode);
+ DriverMode GetDriverMode() const;
+ void SetCurrent(float current);
+ void Enable(bool en);
+ void AppendDriverStatus(const StringRef& reply);
+ uint8_t GetDriverNumber() const { return driverNumber; }
+ bool UpdatePending() const { return registersToUpdate != 0; }
+ void SetStallDetectThreshold(int sgThreshold);
+ void SetStallDetectFilter(bool sgFilter);
+ void SetStallMinimumStepsPerSecond(unsigned int stepsPerSecond);
+ void AppendStallConfig(const StringRef& reply) const;
+
+ 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; }
+ void AbortTransfer();
+
+ uint32_t ReadLiveStatus() const;
+ uint32_t ReadAccumulatedStatus(uint32_t bitsToKeep);
+
+ // Variables used by the ISR
+ static TmcDriverState * volatile currentDriver; // volatile because the ISR changes it
+ static uint32_t transferStartedTime;
+
+ void UartTmcHandler(); // core of the ISR for this driver
+
+private:
+ void UpdateRegister(size_t regIndex, uint32_t regVal);
+ void UpdateChopConfRegister(); // calculate the chopper control register and flag it for sending
+ void UpdateCurrent();
+
+#if TMC22xx_HAS_MUX
+ void SetUartMux();
+ 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
+#else
+ void SetupDMASend(uint8_t regnum, uint32_t outVal, uint8_t crc) __attribute__ ((hot)); // set up the PDC to send a register
+ void SetupDMAReceive(uint8_t regnum, uint8_t crc) __attribute__ ((hot)); // set up the PDC to receive a register
+#endif
+
+ static constexpr unsigned int NumWriteRegisters = 5; // the number of registers that we write to
+ static const uint8_t WriteRegNumbers[NumWriteRegisters]; // the register numbers that we write to
+
+ // Write register numbers are in priority order, most urgent first, in same order as WriteRegNumbers
+ static constexpr unsigned int WriteGConf = 0; // microstepping
+ static constexpr unsigned int WriteSlaveConf = 1; // read response timing
+ static constexpr unsigned int WriteChopConf = 2; // enable/disable and microstep setting
+ static constexpr unsigned int WriteIholdIrun = 3; // current setting
+ static constexpr unsigned int WritePwmConf = 4; // read register select, sense voltage high/low sensitivity
+
+ static constexpr unsigned int NumReadRegisters = 2; // the number of registers that we read from
+ static const uint8_t ReadRegNumbers[NumReadRegisters]; // the register numbers that we read from
+
+ // Read register numbers, in same order as ReadRegNumbers
+ static constexpr unsigned int ReadGStat = 0;
+ static constexpr unsigned int ReadDrvStat = 1;
+
+ 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
+ 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
+
+#if TMC22xx_HAS_MUX
+ static Uart * const uart; // the UART that controls all drivers
+#else
+ Uart *uart; // the UART that controls this driver
+#endif
+
+ // To write a register, we send one 8-byte packet to write it, then a 4-byte packet to ask for the IFCOUNT register, then we receive an 8-byte packet containing IFCOUNT.
+ // This is the message we send - volatile because we care about when it is written
+ static volatile uint8_t sendData[12];
+
+ // Buffer for the message we receive when reading data. The first 4 or 12 bytes bytes are our own transmitted data.
+ static volatile uint8_t receiveData[20];
+
+ uint16_t readErrors; // how many read errors we had
+ uint16_t writeErrors; // how many write errors we had
+ uint16_t numReads; // how many successful reads we had
+ uint16_t numTimeouts; // how many times a transfer timed out
+
+ 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 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
+};
+
+// State structures for all drivers
+static TmcDriverState driverStates[MaxSmartDrivers];
+
+namespace SmartDrivers
+{
+ // Initialise the driver interface and the drivers, leaving each drive disabled.
+ // It is assumed that the drivers are not powered, so driversPowered(true) must be called after calling this before the motors can be moved.
+ void Init(const Pin driverSelectPins[DRIVES], size_t numTmcDrivers)
+ {
+ numTmc51xxDrivers = min<size_t>(numTmcDrivers, MaxSmartDrivers);
+
+ // Make sure the ENN pins are high
+ pinMode(GlobalTmc51xxEnablePin, OUTPUT_HIGH);
+
+ // The pins are already set up for SPI in the pins table
+ ConfigurePin(GetPinDescription(TMC51xxMosiPin));
+ ConfigurePin(GetPinDescription(TMC51xxMisoPin));
+ ConfigurePin(GetPinDescription(TMC51xxSclkPin));
+
+ // Enable the clock to the USART or SPI
+ pmc_enable_periph_clk(ID_TMC51xx_SPI);
+
+#if TMC51xx_USES_USART
+ // Set USART_EXT_DRV in SPI mode, with data changing on the falling edge of the clock and captured on the rising edge
+ USART_TMC51xx->US_IDR = ~0u;
+ USART_TMC51xx->US_CR = US_CR_RSTRX | US_CR_RSTTX | US_CR_RXDIS | US_CR_TXDIS;
+ USART_TMC51xx->US_MR = US_MR_USART_MODE_SPI_MASTER
+ | US_MR_USCLKS_MCK
+ | US_MR_CHRL_8_BIT
+ | US_MR_CHMODE_NORMAL
+ | US_MR_CPOL
+ | US_MR_CLKO;
+ USART_TMC51xx->US_BRGR = VARIANT_MCK/DriversSpiClockFrequency; // set SPI clock frequency
+ USART_TMC51xx->US_CR = US_CR_RSTRX | US_CR_RSTTX | US_CR_RXDIS | US_CR_TXDIS | US_CR_RSTSTA;
+
+ // We need a few microseconds of delay here for the USART to sort itself out before we send any data,
+ // otherwise the processor generates two short reset pulses on its own NRST pin, and resets itself.
+ // 2016-07-07: removed this delay, because we no longer send commands to the TMC2660 drivers immediately.
+ //delay(10);
+#else
+ // Set up the SPI interface with data changing on the falling edge of the clock and captured on the rising edge
+ spi_reset(SPI_TMC51xx); // this clears the transmit and receive registers and puts the SPI into slave mode
+ SPI_TMC51xx->SPI_MR = SPI_MR_MSTR // master mode
+ | SPI_MR_MODFDIS // disable fault detection
+ | SPI_MR_PCS(0); // fixed peripheral select
+
+ // Set SPI mode, clock frequency, CS active after transfer, delay between transfers
+ const uint16_t baud_div = (uint16_t)spi_calc_baudrate_div(DriversSpiClockFrequency, SystemCoreClock);
+ const uint32_t csr = SPI_CSR_SCBR(baud_div) // Baud rate
+ | SPI_CSR_BITS_8_BIT // Transfer bit width
+ | SPI_CSR_DLYBCT(0) // Transfer delay
+ | SPI_CSR_CSAAT // Keep CS low after transfer in case we are slow in writing the next byte
+ | SPI_CSR_CPOL; // clock high between transfers
+ SPI_TMC51xx->SPI_CSR[0] = csr;
+#endif
+
+ driversState = DriversState::noPower;
+ for (size_t driver = 0; driver < numTmc51xxDrivers; ++driver)
+ {
+ driverStates[driver].Init(driver, driverSelectPins[driver]); // axes are mapped straight through to drivers initially
+ }
+
+#if SAME70
+ pmc_enable_periph_clk(ID_XDMAC);
+#endif
+ }
+
+ void SetAxisNumber(size_t driver, uint32_t axisNumber)
+ {
+ if (driver < numTmc51xxDrivers)
+ {
+ driverStates[driver].SetAxisNumber(axisNumber);
+ }
+ }
+
+ void SetCurrent(size_t driver, float current)
+ {
+ if (driver < numTmc51xxDrivers)
+ {
+ driverStates[driver].SetCurrent(current);
+ }
+ }
+
+ void EnableDrive(size_t driver, bool en)
+ {
+ if (driver < numTmc51xxDrivers)
+ {
+ driverStates[driver].Enable(en);
+ }
+ }
+
+ uint32_t GetLiveStatus(size_t driver)
+ {
+ return (driver < numTmc51xxDrivers) ? driverStates[driver].ReadLiveStatus() : 0;
+ }
+
+ uint32_t GetAccumulatedStatus(size_t driver, uint32_t bitsToKeep)
+ {
+ return (driver < numTmc51xxDrivers) ? driverStates[driver].ReadAccumulatedStatus(bitsToKeep) : 0;
+ }
+
+ // Set microstepping and microstep interpolation
+ bool SetMicrostepping(size_t driver, unsigned int microsteps, bool interpolate)
+ {
+ if (driver < numTmc51xxDrivers && microsteps > 0)
+ {
+ // Set the microstepping. We need to determine how many bits right to shift the desired microstepping to reach 1.
+ unsigned int shift = 0;
+ unsigned int uSteps = (unsigned int)microsteps;
+ while ((uSteps & 1) == 0)
+ {
+ uSteps >>= 1;
+ ++shift;
+ }
+ if (uSteps == 1 && shift <= 8)
+ {
+ driverStates[driver].SetMicrostepping(shift, interpolate);
+ return true;
+ }
+ }
+ return false;
+ }
+
+ // Get microstepping and interpolation
+ unsigned int GetMicrostepping(size_t driver, bool& interpolation)
+ {
+ if (driver < numTmc51xxDrivers)
+ {
+ return driverStates[driver].GetMicrostepping(interpolation);
+ }
+ interpolation = false;
+ return 1;
+ }
+
+ bool SetDriverMode(size_t driver, unsigned int mode)
+ {
+ return driver < numTmc51xxDrivers && driverStates[driver].SetDriverMode(mode);
+ }
+
+ DriverMode GetDriverMode(size_t driver)
+ {
+ return (driver < numTmc51xxDrivers) ? driverStates[driver].GetDriverMode() : DriverMode::unknown;
+ }
+
+ bool SetChopperControlRegister(size_t driver, uint32_t ccr)
+ {
+ return driver < numTmc51xxDrivers && driverStates[driver].SetChopConf(ccr);
+ }
+
+ uint32_t GetChopperControlRegister(size_t driver)
+ {
+ return (driver < numTmc51xxDrivers) ? driverStates[driver].GetChopConf() : 0;
+ }
+
+ bool SetOffTime(size_t driver, uint32_t offTime)
+ {
+ return driver < numTmc51xxDrivers && driverStates[driver].SetOffTime(offTime);
+ }
+
+ uint32_t GetOffTime(size_t driver)
+ {
+ return (driver < numTmc51xxDrivers) ? driverStates[driver].GetOffTime() : 0;
+ }
+
+ // Flag that the the drivers have been powered up or down and handle any timeouts
+ // Before the first call to this function with 'powered' true, you must call Init()
+ void Spin(bool powered)
+ {
+ if (driversState == DriversState::noPower)
+ {
+ if (powered)
+ {
+ // Power to the drivers has been provided or restored, so we need to enable and re-initialise them
+ for (size_t drive = 0; drive < numTmc51xxDrivers; ++drive)
+ {
+ driverStates[drive].WriteAll();
+ }
+ driversState = DriversState::initialising;
+ }
+ }
+ else if (powered)
+ {
+ // If no transfer is in progress, kick one off.
+ // If a transfer has timed out, abort it.
+ if (TmcDriverState::currentDriver == nullptr)
+ {
+ // No transfer in progress, so start one
+ if (numTmc51xxDrivers != 0)
+ {
+ // Kick off the first transfer
+ driverStates[0].StartTransfer();
+ }
+ }
+ else if (millis() - TmcDriverState::transferStartedTime > TransferTimeout)
+ {
+ // A UART transfer was started but has timed out
+ TmcDriverState::currentDriver->TransferTimedOut();
+ TmcDriverState::currentDriver->AbortTransfer();
+ uint8_t driverNum = TmcDriverState::currentDriver->GetDriverNumber();
+ TmcDriverState::currentDriver = nullptr;
+
+ ++driverNum;
+ if (driverNum >= numTmc51xxDrivers)
+ {
+ driverNum = 0;
+ }
+ driverStates[driverNum].StartTransfer();
+ }
+
+ if (driversState == DriversState::initialising)
+ {
+ // If all drivers that share the global enable have been initialised, set the global enable
+ bool allInitialised = true;
+ for (size_t i = 0; i < numTmc51xxDrivers; ++i)
+ {
+ if (driverStates[i].UpdatePending())
+ {
+ allInitialised = false;
+ break;
+ }
+ }
+
+ if (allInitialised)
+ {
+ digitalWrite(GlobalTmc51xxEnablePin, LOW);
+ driversState = DriversState::ready;
+ }
+ }
+ }
+ else
+ {
+ // We had power but we lost it
+ digitalWrite(GlobalTmc51xxEnablePin, HIGH); // disable the drivers
+ if (TmcDriverState::currentDriver == nullptr)
+ {
+ TmcDriverState::currentDriver->AbortTransfer();
+ TmcDriverState::currentDriver = nullptr;
+ }
+ driversState = DriversState::noPower;
+ }
+ }
+
+
+ // This is called from the tick ISR, possibly while Spin (with powered either true or false) is being executed
+ void TurnDriversOff()
+ {
+ digitalWrite(GlobalTmc51xxEnablePin, HIGH); // disable the drivers
+ driversState = DriversState::noPower;
+ }
+
+ void SetStallThreshold(size_t driver, int sgThreshold)
+ {
+ if (driver < numTmc51xxDrivers)
+ {
+ driverStates[driver].SetStallDetectThreshold(sgThreshold);
+ }
+ }
+
+ void SetStallFilter(size_t driver, bool sgFilter)
+ {
+ if (driver < numTmc51xxDrivers)
+ {
+ driverStates[driver].SetStallDetectFilter(sgFilter);
+ }
+ }
+
+ void SetStallMinimumStepsPerSecond(size_t driver, unsigned int stepsPerSecond)
+ {
+ if (driver < numTmc51xxDrivers)
+ {
+ driverStates[driver].SetStallMinimumStepsPerSecond(stepsPerSecond);
+ }
+ }
+
+ void SetCoolStep(size_t drive, uint16_t coolStepConfig)
+ {
+ if (drive < numTmc51xxDrivers)
+ {
+ driverStates[drive].SetCoolStep(coolStepConfig);
+ }
+ }
+
+ void AppendStallConfig(size_t driver, const StringRef& reply)
+ {
+ if (driver < numTmc51xxDrivers)
+ {
+ driverStates[driver].AppendStallConfig(reply);
+ }
+ }
+
+ void AppendDriverStatus(size_t driver, const StringRef& reply)
+ {
+ if (driver < numTmc51xxDrivers)
+ {
+ driverStates[driver].AppendDriverStatus(reply);
+ }
+ }
+
+ float GetStandstillCurrentPercent(size_t driver)
+ {
+ return 100.0; // not supported
+ }
+
+ void SetStandstillCurrentPercent(size_t driver, float percent)
+ {
+ // not supported so nothing to see here
+ }
+
+}; // end namespace
+#endif
+
+// End
diff --git a/src/Movement/StepperDrivers/TMC51xx.h b/src/Movement/StepperDrivers/TMC51xx.h
new file mode 100644
index 00000000..587a73cf
--- /dev/null
+++ b/src/Movement/StepperDrivers/TMC51xx.h
@@ -0,0 +1,60 @@
+/*
+ * TMC51xx.h
+ *
+ * Created on: 26 Aug 2018
+ * Author: David
+ */
+
+#ifndef SRC_MOVEMENT_STEPPERDRIVERS_TMC51XX_H_
+#define SRC_MOVEMENT_STEPPERDRIVERS_TMC51XX_H_
+
+#if SUPPORT_TMC51xx
+
+#include "RepRapFirmware.h"
+#include "GCodes/DriverMode.h"
+#include "Pins.h"
+#include "MessageType.h"
+#include "Libraries/General/StringRef.h"
+
+// TMC22xx DRV_STATUS register bit assignments
+const uint32_t TMC_RR_SG = 1 << 24; // stall detected
+const uint32_t TMC_RR_OT = 1 << 25; // over temperature shutdown
+const uint32_t TMC_RR_OTPW = 1 << 26; // over temperature warning
+const uint32_t TMC_RR_S2G = (3 << 27) | (3 << 12); // short to ground indicator (1 bit for each phase) + short to VS indicator
+const uint32_t TMC_RR_OLA = 1 << 29; // open load A
+const uint32_t TMC_RR_OLB = 1 << 30; // open load B
+const uint32_t TMC_RR_STST = 1 << 31; // standstill detected
+
+namespace SmartDrivers
+{
+ void Init(const Pin[DRIVES], size_t numTmcDrivers)
+ pre(numTmcDrivers <= DRIVES);
+ void Spin(bool powered);
+ void TurnDriversOff();
+
+ void SetAxisNumber(size_t driver, uint32_t axisNumber);
+ void SetCurrent(size_t driver, float current);
+ void EnableDrive(size_t driver, bool en);
+ uint32_t GetLiveStatus(size_t driver);
+ uint32_t GetAccumulatedStatus(size_t drive, uint32_t bitsToKeep);
+ bool SetMicrostepping(size_t drive, unsigned int microsteps, bool interpolation);
+ unsigned int GetMicrostepping(size_t drive, bool& interpolation);
+ bool SetDriverMode(size_t driver, unsigned int mode);
+ DriverMode GetDriverMode(size_t driver);
+ bool SetChopperControlRegister(size_t driver, uint32_t ccr);
+ uint32_t GetChopperControlRegister(size_t driver);
+ bool SetOffTime(size_t driver, uint32_t ccr);
+ uint32_t GetOffTime(size_t driver);
+ void SetStallThreshold(size_t driver, int sgThreshold);
+ void SetStallFilter(size_t driver, bool sgFilter);
+ void SetStallMinimumStepsPerSecond(size_t driver, unsigned int stepsPerSecond);
+ void SetCoolStep(size_t driver, uint16_t coolStepConfig);
+ void AppendStallConfig(size_t driver, const StringRef& reply);
+ void AppendDriverStatus(size_t driver, const StringRef& reply);
+ float GetStandstillCurrentPercent(size_t driver);
+ void SetStandstillCurrentPercent(size_t driver, float percent);
+};
+
+#endif
+
+#endif /* SRC_MOVEMENT_STEPPERDRIVERS_TMC51XX_H_ */
diff --git a/src/Networking/ESP8266WiFi/WiFiInterface.cpp b/src/Networking/ESP8266WiFi/WiFiInterface.cpp
index 2eb1efcd..5b6e32d9 100644
--- a/src/Networking/ESP8266WiFi/WiFiInterface.cpp
+++ b/src/Networking/ESP8266WiFi/WiFiInterface.cpp
@@ -33,7 +33,7 @@ static_assert(SsidLength == SsidBufferLength, "SSID lengths in NetworkDefs.h and
# define ESP_SPI_IRQn SPI_IRQn
# define ESP_SPI_HANDLER SPI_Handler
-#elif defined(SAME70_TEST_BOARD)
+#elif defined(DUET3)
# define USE_PDC 0 // use peripheral DMA controller
# define USE_DMAC 0 // use general DMA controller
diff --git a/src/Networking/Network.cpp b/src/Networking/Network.cpp
index 40a9d742..0cc31f1a 100644
--- a/src/Networking/Network.cpp
+++ b/src/Networking/Network.cpp
@@ -44,7 +44,7 @@ static Task<NetworkStackWords> networkTask;
Network::Network(Platform& p) : platform(p), responders(nullptr), nextResponderToPoll(nullptr)
{
-#if defined(SAME70_TEST_BOARD)
+#if defined(DUET3)
interfaces[0] = new LwipEthernetInterface(p);
interfaces[1] = new WiFiInterface(p);
#elif defined(DUET_NG)
diff --git a/src/Networking/Network.h b/src/Networking/Network.h
index 0355e625..473775a8 100644
--- a/src/Networking/Network.h
+++ b/src/Networking/Network.h
@@ -14,7 +14,7 @@
#include "GCodes/GCodeResult.h"
#include "RTOSIface.h"
-#if defined(SAME70_TEST_BOARD)
+#if defined(DUET3)
const size_t NumNetworkInterfaces = 2;
#elif defined(DUET_NG) || defined(DUET_M)
const size_t NumNetworkInterfaces = 1;
diff --git a/src/Pccb/Pins_Pccb.h b/src/Pccb/Pins_Pccb.h
index 79cb1e03..7a702677 100644
--- a/src/Pccb/Pins_Pccb.h
+++ b/src/Pccb/Pins_Pccb.h
@@ -64,7 +64,8 @@ constexpr size_t MaxSmartDrivers = 2; // The maximum number of smart drivers
#endif
-constexpr size_t Heaters = 2; // The number of heaters in the machine. PCCB has no heaters, but we pretend that the LED pins are heaters.
+constexpr size_t NumEndstops = 4; // The number of inputs we have for endstops, filament sensors etc.
+constexpr size_t NumHeaters = 2; // The number of heaters in the machine. PCCB has no heaters, but we pretend that the LED pins are heaters.
constexpr size_t NumExtraHeaterProtections = 4; // The number of extra heater protection instances
constexpr size_t NumThermistorInputs = 2;
@@ -133,14 +134,10 @@ const uint32_t TransferTimeout = 10; // any transfer should complete within
// Endstops
// RepRapFirmware only has a single endstop per axis.
// Gcode defines if it is a max ("high end") or min ("low end") endstop and sets if it is active HIGH or LOW.
-#ifdef PCCB_X5
-constexpr Pin END_STOP_PINS[DRIVES] = { 25, 67, 24, 63, NoPin, NoPin };
-#else
-constexpr Pin END_STOP_PINS[DRIVES] = { 25, 67, 24, 63, NoPin, NoPin, NoPin, NoPin };
-#endif
+constexpr Pin END_STOP_PINS[NumEndstops] = { 25, 67, 24, 63 };
// Heaters and thermistors
-constexpr Pin HEAT_ON_PINS[Heaters] = { 36, 59 }; // these are actually the LED control pins
+constexpr Pin HEAT_ON_PINS[NumHeaters] = { 36, 59 }; // these are actually the LED control pins
constexpr Pin TEMP_SENSE_PINS[NumThermistorInputs] = { 20, 49 }; // Thermistor pin numbers
constexpr Pin VssaSensePin = 19;
constexpr Pin VrefSensePin = 27;
diff --git a/src/Pins.h b/src/Pins.h
index 504d46ae..bd9e1e06 100644
--- a/src/Pins.h
+++ b/src/Pins.h
@@ -15,7 +15,7 @@
# elif defined(__SAM4E8E__)
# define PLATFORM DuetNG
# elif defined(__SAME70Q21__)
-# define PLATFORM SAME70_TEST
+# define PLATFORM Duet3
# elif defined(DUET_M)
# define PLATFORM DuetM
# elif defined(PCCB)
@@ -72,8 +72,12 @@
# define SUPPORT_TMC22xx 0
#endif
-#define HAS_SMART_DRIVERS (SUPPORT_TMC2660 || SUPPORT_TMC22xx)
-#define HAS_STALL_DETECT SUPPORT_TMC2660
+#ifndef SUPPORT_TMC51xx
+# define SUPPORT_TMC51xx 0
+#endif
+
+#define HAS_SMART_DRIVERS (SUPPORT_TMC2660 || SUPPORT_TMC22xx || SUPPORT_TMC51xx)
+#define HAS_STALL_DETECT (SUPPORT_TMC2660 || SUPPORT_TMC51xx)
// HAS_LWIP_NETWORKING refers to Lwip 2 support in the Networking folder, not legacy SAM3XA networking using Lwip 1
#ifndef HAS_LWIP_NETWORKING
diff --git a/src/Platform.cpp b/src/Platform.cpp
index 531932e6..2cf4eb56 100644
--- a/src/Platform.cpp
+++ b/src/Platform.cpp
@@ -36,8 +36,10 @@
#include "Libraries/Math/Isqrt.h"
#include "Wire.h"
-#include "sam/drivers/tc/tc.h"
-#include "sam/drivers/hsmci/hsmci.h"
+#ifndef __LPC17xx__
+# include "sam/drivers/tc/tc.h"
+# include "sam/drivers/hsmci/hsmci.h"
+#endif
#include "sd_mmc.h"
@@ -47,6 +49,9 @@
#if SUPPORT_TMC22xx
# include "Movement/StepperDrivers/TMC22xx.h"
#endif
+#if SUPPORT_TMC51xx
+# include "Movement/StepperDrivers/TMC51xx.h"
+#endif
#if HAS_WIFI_NETWORKING
# include "FirmwareUpdater.h"
@@ -320,6 +325,13 @@ void Platform::Init()
pinMode(SpiFLASHcsPin,OUTPUT_HIGH); // Init Spi FLASH Cs pin, not implemented, default unselected
#endif
+#if defined(__LPC17xx__)
+# if HAS_DRIVER_CURRENT_CONTROL
+ mcp4451.begin();
+# endif
+ Microstepping::Init(); // basic class to remember the Microstepping.
+#endif
+
// DRIVES
ARRAY_INIT(endStopPins, END_STOP_PINS);
ARRAY_INIT(maxFeedrates, MAX_FEEDRATES);
@@ -352,15 +364,17 @@ void Platform::Init()
}
// Motors
+#ifndef __LPC17xx__
// Disable parallel writes to all pins. We re-enable them for the step pins.
PIOA->PIO_OWDR = 0xFFFFFFFF;
PIOB->PIO_OWDR = 0xFFFFFFFF;
PIOC->PIO_OWDR = 0xFFFFFFFF;
-#ifdef PIOD
+# ifdef PIOD
PIOD->PIO_OWDR = 0xFFFFFFFF;
-#endif
-#ifdef PIOE
+# endif
+# ifdef PIOE
PIOE->PIO_OWDR = 0xFFFFFFFF;
+# endif
#endif
for (size_t drive = 0; drive < DRIVES; drive++)
@@ -384,27 +398,29 @@ void Platform::Init()
pinMode(DIRECTION_PINS[drive], OUTPUT_LOW);
pinMode(ENABLE_PINS[drive], OUTPUT_HIGH); // this is OK for the TMC2660 CS pins too
+#ifndef __LPC17xx__
const PinDescription& pinDesc = g_APinDescription[STEP_PINS[drive]];
pinDesc.pPort->PIO_OWER = pinDesc.ulPin; // enable parallel writes to the step pins
-
+#endif
motorCurrents[drive] = 0.0;
motorCurrentFraction[drive] = 1.0;
driverState[drive] = DriverStatus::disabled;
+ }
- // Enable pullup resistors on endstop inputs here if necessary.
-#if defined(DUET_NG) || defined(DUET_06_085)
- // The Duets have hardware pullup resistors/LEDs except for the two on the CONN_LCD connector.
- // They have RC filtering on the main endstop inputs, so best not to enable the pullup resistors on these.
- // 2017-12-19: some users are having trouble with the endstops not being recognised in recent firmware versions.
- // Probably the LED+resistor isn't pulling them up fast enough. So enable the pullup resistors again.
- // Note: if we don't have a DueX board connected, the pullups on endstop inputs 5-9 must always be enabled.
- // Also the pullups on endstop inputs 10-11 must always be enabled.
- setPullup(endStopPins[drive], true); // enable pullup on endstop input
-#elif defined(__RADDS__) || defined(__ALLIGATOR__)
- // I don't know whether RADDS and Alligator have hardware pullup resistors or not. I'll assume they might not.
- setPullup(endStopPins[drive], true);
-#endif
+#if defined(DUET_NG) || defined(DUET_06_085) || defined(__RADDS__) || defined(__ALLIGATOR__)
+ // Enable pullup resistors on endstop inputs here if necessary.
+ // The Duets have hardware pullup resistors/LEDs except for the two on the CONN_LCD connector.
+ // They have RC filtering on the main endstop inputs, so best not to enable the pullup resistors on these.
+ // 2017-12-19: some users are having trouble with the endstops not being recognised in recent firmware versions.
+ // Probably the LED+resistor isn't pulling them up fast enough. So enable the pullup resistors again.
+ // Note: if we don't have a DueX board connected, the pullups on endstop inputs 5-9 must always be enabled.
+ // Also the pullups on endstop inputs 10-11 must always be enabled.
+ // I don't know whether RADDS and Alligator have hardware pullup resistors or not. I'll assume they might not.
+ for (size_t endstop = 0; endstop < NumEndstops; ++endstop)
+ {
+ setPullup(endStopPins[endstop], true); // enable pullup on endstop input
}
+#endif
for (uint32_t& entry : slowDriverStepTimingClocks)
{
@@ -502,7 +518,7 @@ void Platform::Init()
setPullup(SpiTempSensorCsPins[i], true);
}
- for (size_t heater = 0; heater < Heaters; heater++)
+ for (size_t heater = 0; heater < NumHeaters; heater++)
{
// pinMode is safe to call when the pin is NoPin, so we don't need to check it here
pinMode(HEAT_ON_PINS[heater],
@@ -636,7 +652,7 @@ void Platform::InitZProbe()
case ZProbeType::e0Switch:
AnalogInEnableChannel(zProbeAdcChannel, false);
pinMode(zProbePin, INPUT_PULLUP);
- pinMode(endStopPins[E0_AXIS], INPUT);
+ pinMode(GetEndstopPin(E0_AXIS), INPUT);
pinMode(zProbeModulationPin, OUTPUT_LOW); // we now set the modulation output high during probing only when using probe types 4 and higher
break;
@@ -653,7 +669,7 @@ void Platform::InitZProbe()
case ZProbeType::e1Switch:
AnalogInEnableChannel(zProbeAdcChannel, false);
pinMode(zProbePin, INPUT_PULLUP);
- pinMode(endStopPins[E0_AXIS + 1], INPUT);
+ pinMode(GetEndstopPin(E0_AXIS + 1), INPUT);
pinMode(zProbeModulationPin, OUTPUT_LOW); // we now set the modulation output high during probing only when using probe types 4 and higher
break;
@@ -1354,6 +1370,7 @@ void Platform::Spin()
// The tick ISR also looks for over-voltage events, but it just disables the driver without changing driversPowerd or numOverVoltageEvents
if (driversPowered)
{
+# if HAS_VOLTAGE_MONITOR
if (currentVin < driverPowerOffAdcReading)
{
driversPowered = false;
@@ -1367,6 +1384,7 @@ void Platform::Spin()
lastOverVoltageValue = currentVin; // save this because the voltage may have changed by the time we report it
}
else
+# endif
{
// Check one TMC2660 or TMC2224 for temperature warning or temperature shutdown
if (enableValues[nextDriveToPoll] >= 0) // don't poll driver if it is flagged "no poll"
@@ -1471,10 +1489,12 @@ void Platform::Spin()
}
}
}
+# if HAS_VOLTAGE_MONITOR
else if (currentVin >= driverPowerOnAdcReading && currentVin <= driverNormalVoltageAdcReading)
{
driversPowered = true;
}
+# endif
SmartDrivers::Spin(driversPowered);
#endif
@@ -1900,13 +1920,15 @@ void NETWORK_TC_HANDLER()
void Platform::InitialiseInterrupts()
{
-#if SAM4E || SAM7E
+#if SAM4E || SAM7E || __LPC17xx__
NVIC_SetPriority(WDT_IRQn, NvicPriorityWatchdog); // set priority for watchdog interrupts
#endif
-#ifdef RTOS
+#if HAS_HIGH_SPEED_SD && defined(RTOS)
NVIC_SetPriority(HSMCI_IRQn, NvicPriorityHSMCI); // set priority for SD interface interrupts
-#else
+#endif
+
+#ifndef RTOS
// Set the tick interrupt to the highest priority. We need to to monitor the heaters and kick the watchdog.
NVIC_SetPriority(SysTick_IRQn, NvicPrioritySystick); // set priority for tick interrupts
#endif
@@ -1942,17 +1964,34 @@ void Platform::InitialiseInterrupts()
// 1.524us resolution on the Duet 085 (84MHz clock)
// 1.067us resolution on the Duet WiFi (120MHz clock)
// 0.853us resolution on the SAM E70 (150MHz clock)
+
+#if __LPC17xx__
+ //LPC has 32bit timers
+ //Using the same 128 divisor (as also specified in DDA)
+ //LPC Timers default to /4 --> (SystemCoreClock/4)
+ const uint32_t res = (VARIANT_MCK/128); // 1.28us for 100MHz (LPC1768) and 1.067us for 120MHz (LPC1769)
+
+ //Start a free running Timer using Match Registers 0 and 1 to generate interrupts
+ LPC_SC->PCONP |= ((uint32_t) 1<<SBIT_PCTIM0); // Ensure the Power bit is set for the Timer
+ STEP_TC->MCR = 0; //disable all MRx interrupts
+ STEP_TC->PR = (getPclk(PCLK_TIMER0) / res) - 1; // Set the LPC Prescaler (i.e. TC increment every 32 TimerClock Ticks)
+ STEP_TC->TC = 0x00; // Restart the Timer Count
+ NVIC_SetPriority(STEP_TC_IRQN, NvicPriorityStep); // set high priority for this IRQ; it's time-critical
+ NVIC_EnableIRQ(STEP_TC_IRQN);
+ STEP_TC->TCR = (1 <<SBIT_CNTEN); // Start Timer
+#else
pmc_set_writeprotect(false);
pmc_enable_periph_clk(STEP_TC_ID);
tc_init(STEP_TC, STEP_TC_CHAN, TC_CMR_WAVE | TC_CMR_WAVSEL_UP | TC_CMR_TCCLKS_TIMER_CLOCK4 | TC_CMR_EEVT_XC0); // must set TC_CMR_EEVT nonzero to get RB compare interrupts
STEP_TC->TC_CHANNEL[STEP_TC_CHAN].TC_IDR = ~(uint32_t)0; // interrupts disabled for now
#if SAM4S || SAME70 // if 16-bit TCs
- STEP_TC->TC_CHANNEL[STEP_TC_CHAN].TC_IER = TC_IER_COVFS; // enable the overflow interrupt so that we can use it to extend the count to 32-bits
+ STEP_TC->TC_CHANNEL[STEP_TC_CHAN].TC_IER = TC_IER_COVFS; // enable the overflow interrupt so that we can use it to extend the count to 32-bits
#endif
tc_start(STEP_TC, STEP_TC_CHAN);
tc_get_status(STEP_TC, STEP_TC_CHAN); // clear any pending interrupt
NVIC_SetPriority(STEP_TC_IRQN, NvicPriorityStep); // set priority for this IRQ
NVIC_EnableIRQ(STEP_TC_IRQN);
+#endif
#if HAS_LWIP_NETWORKING
pmc_enable_periph_clk(NETWORK_TC_ID);
@@ -1981,14 +2020,19 @@ void Platform::InitialiseInterrupts()
# endif
#endif
+#if __LPC17xx__
+ //SD: Int for GPIO pins on port 0 and 2 share EINT3
+ NVIC_SetPriority(EINT3_IRQn, NvicPriorityPins);
+#else
NVIC_SetPriority(PIOA_IRQn, NvicPriorityPins);
NVIC_SetPriority(PIOB_IRQn, NvicPriorityPins);
NVIC_SetPriority(PIOC_IRQn, NvicPriorityPins);
-#ifdef ID_PIOD
+# ifdef ID_PIOD
NVIC_SetPriority(PIOD_IRQn, NvicPriorityPins);
-#endif
-#ifdef ID_PIOE
+# endif
+# ifdef ID_PIOE
NVIC_SetPriority(PIOE_IRQn, NvicPriorityPins);
+# endif
#endif
#if SAME70
@@ -1997,12 +2041,17 @@ void Platform::InitialiseInterrupts()
NVIC_SetPriority(UDP_IRQn, NvicPriorityUSB);
#elif SAM3XA
NVIC_SetPriority(UOTGHS_IRQn, NvicPriorityUSB);
+#elif __LPC17xx__
+ NVIC_SetPriority(USB_IRQn, NvicPriorityUSB);
#else
# error
#endif
#if defined(DUET_NG) || defined(DUET_M) || defined(DUET_06_085)
NVIC_SetPriority(I2C_IRQn, NvicPriorityTwi);
+#elif __LPC17xx__
+ NVIC_SetPriority(I2C0_IRQn, NvicPriorityTwi);
+ NVIC_SetPriority(I2C1_IRQn, NvicPriorityTwi);
#endif
// Tick interrupt for ADC conversions
@@ -2010,9 +2059,13 @@ void Platform::InitialiseInterrupts()
currentFilterNumber = 0;
// Set up the timeout of the regulator watchdog, and set up the backup watchdog if there is one
+#if __LPC17xx__
+ wdt_init(1); // set wdt to 1 second. reset the processor on a watchdog fault
+#else
// The clock frequency for both watchdogs is 32768/128 = 256Hz
const uint16_t timeout = 32768/128; // set watchdog timeout to 1 second (max allowed value is 4095 = 16 seconds)
wdt_init(WDT, WDT_MR_WDRSTEN, timeout, timeout); // reset the processor on a watchdog fault
+#endif
#if SAM4E || SAME70
// The RSWDT must be initialised *after* the main WDT
@@ -2098,23 +2151,43 @@ void Platform::Diagnostics(MessageType mtype)
Message(mtype, "=== Platform ===\n");
+#ifndef __LPC17xx__
// 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",
-#ifdef DUET_NG
+# 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
+# else
"reset button",
-#endif
+# endif
"?", "?", "?" };
MessageF(mtype, "Last reset %02d:%02d:%02d ago, cause: %s\n",
(unsigned int)(now/3600), (unsigned int)((now % 3600)/60), (unsigned int)(now % 60),
resetReasons[(REG_RSTC_SR & RSTC_SR_RSTTYP_Msk) >> RSTC_SR_RSTTYP_Pos]);
+#endif //end ifndef __LPC17xx__
// Show the reset code stored at the last software reset
{
+#if __LPC17xx__
+ SoftwareResetData srdBuf[1];
+ int slot = -1;
+
+ for (int s = SoftwareResetData::numberOfSlots - 1; s >= 0; s--)
+ {
+ SoftwareResetData *sptr = reinterpret_cast<SoftwareResetData *>(LPC_GetSoftwareResetDataSlotPtr(s));
+ if(sptr->magic != 0xFFFF)
+ {
+ //slot = s;
+ MessageF(mtype, "Flash Slot[%d]: \n", s);
+ slot=0;// we only have 1 slot in the array, set this to zero to be compatible with existing code below
+ //copy the data into srdBuff
+ LPC_ReadSoftwareResetDataSlot(s, &srdBuf[0], sizeof(srdBuf[0]));
+ break;
+ }
+ }
+#else
SoftwareResetData srdBuf[SoftwareResetData::numberOfSlots];
memset(srdBuf, 0, sizeof(srdBuf));
int slot = -1;
@@ -2141,6 +2214,7 @@ void Platform::Diagnostics(MessageType mtype)
}
while (slot >= 0 && srdBuf[slot].magic == 0xFFFF);
}
+#endif
if (slot >= 0 && srdBuf[slot].magic == SoftwareResetData::magicValue)
{
@@ -2460,6 +2534,8 @@ bool Platform::DiagnosticTest(GCodeBuffer& gb, const StringRef& reply, int d)
(void)*(reinterpret_cast<const volatile char*>(0x20800000));
#elif SAM3XA
(void)*(reinterpret_cast<const volatile char*>(0x20200000));
+#elif __LPC17xx__
+ Message(WarningMessage, "TODO:: Skipping test on LPC");//????
#else
# error
#endif
@@ -2584,7 +2660,7 @@ void Platform::UpdateConfiguredHeaters()
}
// Check tool heaters
- for (size_t heater = 0; heater < Heaters; heater++)
+ for (size_t heater = 0; heater < NumHeaters; heater++)
{
if (reprap.IsHeaterAssignedToTool(heater))
{
@@ -2649,7 +2725,7 @@ EndStopHit Platform::Stopped(size_t drive) const
#endif
case EndStopInputType::activeLow:
- if (endStopPins[drive] != NoPin)
+ if (drive < NumEndstops && endStopPins[drive] != NoPin)
{
const bool b = IoPort::ReadPin(endStopPins[drive]);
return (b) ? EndStopHit::noStop : (endStopPos[drive] == EndStopPosition::highEndStop) ? EndStopHit::highHit : EndStopHit::lowHit;
@@ -2657,7 +2733,7 @@ EndStopHit Platform::Stopped(size_t drive) const
break;
case EndStopInputType::activeHigh:
- if (endStopPins[drive] != NoPin)
+ if (drive < NumEndstops && endStopPins[drive] != NoPin)
{
const bool b = !IoPort::ReadPin(endStopPins[drive]);
return (b) ? EndStopHit::noStop : (endStopPos[drive] == EndStopPosition::highEndStop) ? EndStopHit::highHit : EndStopHit::lowHit;
@@ -2681,14 +2757,14 @@ EndStopHit Platform::Stopped(size_t drive) const
// Return the state of the endstop input, regardless of whether we are actually using it as an endstop
bool Platform::EndStopInputState(size_t drive) const
{
- return endStopPins[drive] != NoPin && IoPort::ReadPin(endStopPins[drive]);
+ return drive < NumEndstops && endStopPins[drive] != NoPin && IoPort::ReadPin(endStopPins[drive]);
}
-// Get the statues of all the endstop inputs, regardless of what they are used for. Used for triggers.
+// Get the statuses of all the endstop inputs, regardless of what they are used for. Used for triggers.
uint32_t Platform::GetAllEndstopStates() const
{
uint32_t rslt = 0;
- for (unsigned int drive = 0; drive < DRIVES; ++drive)
+ for (unsigned int drive = 0; drive < NumEndstops; ++drive)
{
const Pin pin = endStopPins[drive];
if (pin != NoPin && IoPort::ReadPin(pin))
@@ -3020,6 +3096,23 @@ void Platform::UpdateMotorCurrent(size_t driver)
{
dacPiggy.setChannel(7-driver, current * 0.102);
}
+#elif defined(__LPC17xx__)
+# if HAS_DRIVER_CURRENT_CONTROL
+ //Has digipots to set current control for drivers
+ //Current is in mA
+ const uint16_t pot = (unsigned short) (current * digipotFactor / 1000);
+ if (pot > 256) { pot = 255; }
+ if (driver < 4)
+ {
+ mcp4451.setMCP4461Address(0x2C); //A0 and A1 Grounded. (001011 00)
+ mcp4451.setVolatileWiper(POT_WIPES[driver], pot);
+ }
+ else
+ {
+ mcp4451.setMCP4461Address(0x2D); //A0 Vcc, A1 Grounded. (001011 01)
+ mcp4451.setVolatileWiper(POT_WIPES[driver-4], pot);
+ }
+# endif
#else
// otherwise we can't set the motor current
#endif
@@ -3087,6 +3180,8 @@ bool Platform::SetDriverMicrostepping(size_t driver, unsigned int microsteps, in
}
#elif defined(__ALLIGATOR__)
return Microstepping::Set(driver, microsteps); // no mode in Alligator board
+#elif __LPC17xx__
+ return Microstepping::Set(driver, microsteps);
#else
// Assume only x16 microstepping supported
return microsteps == 16;
@@ -3130,6 +3225,9 @@ unsigned int Platform::GetDriverMicrostepping(size_t driver, bool& interpolation
#elif defined(__ALLIGATOR__)
interpolation = false;
return Microstepping::Read(driver); // no mode, no interpolation for Alligator
+#elif __LPC17xx__
+ interpolation = false;
+ return Microstepping::Read(driver); //get the value we saved
#else
interpolation = false;
return 16;
@@ -3276,7 +3374,11 @@ void Platform::SetFanValue(size_t fan, float speed)
void Platform::EnableSharedFan(bool enable)
{
const size_t sharedFanNumber = NUM_FANS - 1;
- fans[sharedFanNumber].Init((enable) ? COOLING_FAN_PINS[sharedFanNumber] : NoPin, FansHardwareInverted(sharedFanNumber), DefaultFanPwmFreq);
+ fans[sharedFanNumber].Init(
+ (enable) ? COOLING_FAN_PINS[sharedFanNumber] : NoPin,
+ (enable) ? Fan0LogicalPin + sharedFanNumber : NoLogicalPin,
+ FansHardwareInverted(sharedFanNumber),
+ DefaultFanPwmFreq);
}
#endif
@@ -3347,7 +3449,7 @@ void Platform::InitFans()
SetBit(bedAndChamberHeaterMask, chamberHeater);
}
}
- fans[1].SetHeatersMonitored(LowestNBits<Fan::HeatersMonitoredBitmap>(Heaters) & ~bedAndChamberHeaterMask);
+ fans[1].SetHeatersMonitored(LowestNBits<Fan::HeatersMonitoredBitmap>(NumHeaters) & ~bedAndChamberHeaterMask);
fans[1].SetPwm(1.0); // set it full on
#elif defined(PCCB)
// Fan 3 needs to be set explicitly to zero PWM, otherwise it turns on because the MCU output pin isn't set low
@@ -3863,8 +3965,8 @@ void Platform::SetBoardType(BoardType bt)
{
if (bt == BoardType::Auto)
{
-#if defined(SAME70_TEST_BOARD)
- board = BoardType::SamE70TestBoard;
+#if defined(DUET3)
+ board = BoardType::Duet3_10;
#elif defined(DUET_NG)
// Get ready to test whether the Ethernet module is present, so that we avoid additional delays
pinMode(EspResetPin, OUTPUT_LOW); // reset the WiFi module or the W5500. We assume that this forces the ESP8266 UART output pin to high impedance.
@@ -3909,6 +4011,8 @@ void Platform::SetBoardType(BoardType bt)
board = BoardType::Alligator_2;
#elif defined(PCCB)
board = BoardType::PCCB_10;
+#elif defined(__LPC17xx__)
+ board = BoardType::Lpc;
#else
# error Undefined board type
#endif
@@ -3930,8 +4034,8 @@ const char* Platform::GetElectronicsString() const
{
switch (board)
{
-#if defined(SAME70_TEST_BOARD)
- case BoardType::SamE70TestBoard: return "SAM E70 prototype 1";
+#if defined(DUET3)
+ case BoardType::Duet3_10: return "Duet 3 prototype 1";
#elif defined(DUET_NG)
case BoardType::DuetWiFi_10: return "Duet WiFi 1.0 or 1.01";
case BoardType::DuetWiFi_102: return "Duet WiFi 1.02 or later";
@@ -3949,6 +4053,8 @@ const char* Platform::GetElectronicsString() const
case BoardType::Alligator_2: return "Alligator r2";
#elif defined(PCCB)
case BoardType::PCCB_10: return "PCCB 1.0";
+#elif defined(__LPC17xx__)
+ case BoardType::Lpc: return LPC_ELECTRONICS_STRING;
#else
# error Undefined board type
#endif
@@ -3961,8 +4067,8 @@ const char* Platform::GetBoardString() const
{
switch (board)
{
-#if defined(SAME70_TEST_BOARD)
- case BoardType::SamE70TestBoard: return "same70prototype1";
+#if defined(DUET3)
+ case BoardType::Duet3_10: return "duet3proto";
#elif defined(DUET_NG)
case BoardType::DuetWiFi_10: return "duetwifi10";
case BoardType::DuetWiFi_102: return "duetwifi102";
@@ -3980,6 +4086,8 @@ const char* Platform::GetBoardString() const
case BoardType::Alligator_2: return "alligator2";
#elif defined(PCCB)
case BoardType::PCCB_10: return "pccb10";
+#elif defined(__LPC17xx__)
+ case BoardType::Lpc: return LPC_BOARD_STRING;
#else
# error Undefined board type
#endif
@@ -4002,7 +4110,7 @@ bool Platform::GetFirmwarePin(LogicalPin logicalPin, PinAccess access, Pin& firm
{
firmwarePin = NoPin; // assume failure
invert = false; // this is the common case
- if (logicalPin >= Heater0LogicalPin && logicalPin < Heater0LogicalPin + (int)Heaters) // pins 0-9 correspond to heater channels
+ if (logicalPin >= Heater0LogicalPin && logicalPin < Heater0LogicalPin + (int)NumHeaters) // pins 0-9 correspond to heater channels
{
// For safety, we don't allow a heater channel to be used for servos until the heater has been disabled
if (!reprap.GetHeat().IsHeaterEnabled(logicalPin - Heater0LogicalPin))
@@ -4095,7 +4203,7 @@ bool Platform::GetFirmwarePin(LogicalPin logicalPin, PinAccess access, Pin& firm
// For fan pin mapping
bool Platform::TranslateFanPin(LogicalPin logicalPin, Pin& firmwarePin, bool& invert) const
{
- if (logicalPin >= Heater0LogicalPin && logicalPin < Heater0LogicalPin + (int)Heaters) // pins 0-9 correspond to heater channels
+ if (logicalPin >= Heater0LogicalPin && logicalPin < Heater0LogicalPin + (int)NumHeaters) // pins 0-9 correspond to heater channels
{
// For safety, we don't allow a heater channel to be used for fans until the heater has been disabled
if (!reprap.GetHeat().IsHeaterEnabled(logicalPin - Heater0LogicalPin))
@@ -4122,7 +4230,7 @@ bool Platform::TranslateFanPin(LogicalPin logicalPin, Pin& firmwarePin, bool& in
// Append the name of a logical pin to a string
void Platform::AppendPinName(LogicalPin logicalPin, const StringRef& str) const
{
- if (logicalPin >= Heater0LogicalPin && logicalPin < Heater0LogicalPin + (int)Heaters) // pins 0-9 correspond to heater channels
+ if (logicalPin >= Heater0LogicalPin && logicalPin < Heater0LogicalPin + (int)NumHeaters) // pins 0-9 correspond to heater channels
{
str.catf("H%u", logicalPin - Heater0LogicalPin);
}
@@ -4480,6 +4588,9 @@ uint32_t Platform::Random()
#endif
// Step pulse timer interrupt
+#if __LPC17xx__
+extern "C"
+#endif
void STEP_TC_HANDLER() __attribute__ ((hot));
#if SAM4S || SAME70
@@ -4529,6 +4640,32 @@ void STEP_TC_HANDLER()
SoftTimer::Interrupt();
}
}
+#elif __LPC17xx__
+ uint32_t regval = STEP_TC->IR;
+ //find which Match Register triggered the interrupt
+ if (regval & (1 << SBIT_MRI0_IFM)) //Interrupt flag for match channel 0.
+ {
+ STEP_TC->IR |= (1<<SBIT_MRI0_IFM); //clear interrupt on MR0 (setting bit will clear int)
+ STEP_TC->MCR &= ~(1<<SBIT_MR0I); //Disable Int on MR0
+
+# ifdef MOVE_DEBUG
+ ++numInterruptsExecuted;
+ lastInterruptTime = Platform::GetInterruptClocks();
+# endif
+ reprap.GetMove().Interrupt(); // execute the step interrupt
+ }
+
+ if (regval & (1 << SBIT_MRI1_IFM)) //Interrupt flag for match channel 1.
+ {
+ STEP_TC->IR |= (1<<SBIT_MRI1_IFM); //clear interrupt
+ STEP_TC->MCR &= ~(1<<SBIT_MR1I); //Disable Int on MR1
+# ifdef SOFT_TIMER_DEBUG
+ ++numSoftTimerInterruptsExecuted;
+# endif
+ SoftTimer::Interrupt();
+ }
+//end __LPC17xx__
+
#else
uint32_t tcsr = STEP_TC->TC_CHANNEL[STEP_TC_CHAN].TC_SR; // read the status register, which clears the status bits, and or-in any pending status bits
tcsr &= STEP_TC->TC_CHANNEL[STEP_TC_CHAN].TC_IMR; // select only enabled interrupts
@@ -4592,6 +4729,10 @@ void STEP_TC_HANDLER()
return true; // tell the caller to simulate an interrupt instead
}
+#ifdef __LPC17xx__
+ STEP_TC->MR0 = tim;
+ STEP_TC->MCR |= (1 << SBIT_MR0I); // Enable Int on MR0 match
+#else
STEP_TC->TC_CHANNEL[STEP_TC_CHAN].TC_RA = tim; // set up the compare register
// We would like to clear any pending step interrupt. To do this, we must read the TC status register.
@@ -4599,6 +4740,7 @@ void STEP_TC_HANDLER()
// So we don't, and the step ISR must allow for getting called prematurely.
STEP_TC->TC_CHANNEL[STEP_TC_CHAN].TC_IER = TC_IER_CPAS; // enable the interrupt
cpu_irq_restore(flags);
+#endif
#ifdef MOVE_DEBUG
++numInterruptsScheduled;
@@ -4611,9 +4753,13 @@ void STEP_TC_HANDLER()
// Make sure we get no step interrupts
/*static*/ void Platform::DisableStepInterrupt()
{
+#ifdef __LPC17xx__
+ STEP_TC->MCR &= ~(1<<SBIT_MR0I); //Disable Int on MR0
+#else
STEP_TC->TC_CHANNEL[STEP_TC_CHAN].TC_IDR = TC_IER_CPAS;
-#if SAM4S || SAME70
+# if SAM4S || SAME70
stepTimerPendingStatus &= ~TC_SR_CPAS;
+# endif
#endif
}
@@ -4628,12 +4774,17 @@ void STEP_TC_HANDLER()
return true; // tell the caller to simulate an interrupt instead
}
+#ifdef __LPC17xx__
+ STEP_TC->MR1 = tim; //set MR1 compare register
+ STEP_TC->MCR |= (1<<SBIT_MR1I); // Int on MR1 match
+#else
STEP_TC->TC_CHANNEL[STEP_TC_CHAN].TC_RB = tim; // set up the compare register
// We would like to clear any pending step interrupt. To do this, we must read the TC status register.
// Unfortunately, this would clear any other pending interrupts from the same TC.
// So we don't, and the timer ISR must allow for getting called prematurely.
STEP_TC->TC_CHANNEL[STEP_TC_CHAN].TC_IER = TC_IER_CPBS; // enable the interrupt
+#endif
cpu_irq_restore(flags);
#ifdef SOFT_TIMER_DEBUG
@@ -4645,9 +4796,13 @@ void STEP_TC_HANDLER()
// Make sure we get no step interrupts
/*static*/ void Platform::DisableSoftTimerInterrupt()
{
+#ifdef __LPC17xx__
+ STEP_TC->MCR &= ~(1<<SBIT_MR1I); //Disable Int on MR1
+#else
STEP_TC->TC_CHANNEL[STEP_TC_CHAN].TC_IDR = TC_IER_CPBS;
-#if SAM4S || SAME70
+# if SAM4S || SAME70
stepTimerPendingStatus &= ~TC_SR_CPBS;
+# endif
#endif
}
diff --git a/src/Platform.h b/src/Platform.h
index be703e1b..1f282663 100644
--- a/src/Platform.h
+++ b/src/Platform.h
@@ -113,8 +113,8 @@ constexpr uint32_t maxPidSpinDelay = 5000; // Maximum elapsed time in millisec
enum class BoardType : uint8_t
{
Auto = 0,
-#if defined(SAME70_TEST_BOARD)
- SamE70TestBoard = 1
+#if defined(DUET3)
+ Duet3_10 = 1
#elif defined(DUET_NG)
DuetWiFi_10 = 1,
DuetWiFi_102 = 2,
@@ -731,7 +731,7 @@ private:
volatile DriverStatus driverState[DRIVES];
bool directions[DRIVES];
int8_t enableValues[DRIVES];
- Pin endStopPins[DRIVES];
+ Pin endStopPins[NumEndstops];
float maxFeedrates[DRIVES];
float accelerations[DRIVES];
float driveStepsPerUnit[DRIVES];
@@ -1184,7 +1184,7 @@ inline uint16_t Platform::GetRawZProbeReading() const
case ZProbeType::e0Switch:
{
- const bool b = IoPort::ReadPin(endStopPins[E0_AXIS]);
+ const bool b = IoPort::ReadPin(GetEndstopPin(E0_AXIS));
return (b) ? 4000 : 0;
}
@@ -1195,7 +1195,7 @@ inline uint16_t Platform::GetRawZProbeReading() const
case ZProbeType::e1Switch:
{
- const bool b = IoPort::ReadPin(endStopPins[E0_AXIS + 1]);
+ const bool b = IoPort::ReadPin(GetEndstopPin(E0_AXIS + 1));
return (b) ? 4000 : 0;
}
@@ -1249,7 +1249,7 @@ inline OutputBuffer *Platform::GetAuxGCodeReply()
// The bitmaps for various controller electronics are organised like this:
// Duet WiFi:
// All step pins are on port D, so the bitmap is just the map of step bits in port D.
-// Duet Maestro and PCCB:
+// Duet Maestro, PCCB and Duet 3:
// All step pins are on port C, so the bitmap is just the map of step bits in port C.
// Duet 0.6 and 0.8.5:
// Step pins are PA0, PC7,9,11,14,25,29 and PD0,3.
@@ -1269,11 +1269,11 @@ inline OutputBuffer *Platform::GetAuxGCodeReply()
return 0;
}
-#if defined(SAME70_TEST_BOARD)
- return 0; // TODO assign step pins
-#else
+#ifndef __LPC17xx__ //LPC doesn't need pinDesc
const PinDescription& pinDesc = g_APinDescription[STEP_PINS[driver]];
-#if defined(DUET_NG) || defined(DUET_M) || defined(PCCB)
+#endif
+
+#if defined(DUET_NG) || defined(DUET_M) || defined(PCCB) || defined(DUET3)
return pinDesc.ulPin;
#elif defined(DUET_06_085)
return (pinDesc.pPort == PIOA) ? pinDesc.ulPin << 1 : pinDesc.ulPin;
@@ -1281,10 +1281,11 @@ inline OutputBuffer *Platform::GetAuxGCodeReply()
return (pinDesc.pPort == PIOC) ? pinDesc.ulPin << 1 : pinDesc.ulPin;
#elif defined(__ALLIGATOR__)
return pinDesc.ulPin;
+# elif defined(__LPC17xx__)
+ return 1u << STEP_PIN_PORT2_POS[driver];
#else
# error Unknown board
#endif
-#endif
}
// Set the specified step pins high
@@ -1292,11 +1293,9 @@ inline OutputBuffer *Platform::GetAuxGCodeReply()
// We rely on only those port bits that are step pins being set in the PIO_OWSR register of each port
/*static*/ inline void Platform::StepDriversHigh(uint32_t driverMap)
{
-#if defined(SAME70_TEST_BOARD)
- // TODO
-#elif defined(DUET_NG)
+#if defined(DUET_NG)
PIOD->PIO_ODSR = driverMap; // on Duet WiFi all step pins are on port D
-#elif defined(DUET_M) || defined(PCCB)
+#elif defined(DUET_M) || defined(PCCB) || defined(DUET3)
PIOC->PIO_ODSR = driverMap; // on Duet Maestro all step pins are on port C
#elif defined(DUET_06_085)
PIOD->PIO_ODSR = driverMap;
@@ -1311,6 +1310,11 @@ inline OutputBuffer *Platform::GetAuxGCodeReply()
PIOB->PIO_ODSR = driverMap;
PIOD->PIO_ODSR = driverMap;
PIOC->PIO_ODSR = driverMap;
+#elif defined(__LPC17xx__)
+ //On Azteeg X5 Mini all step pins are on Port 2
+ //On Smoothieboard all step pins are on Port 2
+ //On ReArm all step pins are on Port 2
+ LPC_GPIO2->FIOSET = driverMap;
#else
# error Unknown board
#endif
@@ -1321,11 +1325,9 @@ inline OutputBuffer *Platform::GetAuxGCodeReply()
// We rely on only those port bits that are step pins being set in the PIO_OWSR register of each port
/*static*/ inline void Platform::StepDriversLow()
{
-#if defined(SAME70_TEST_BOARD)
- // TODO
-#elif defined(DUET_NG)
+#if defined(DUET_NG)
PIOD->PIO_ODSR = 0; // on Duet WiFi all step pins are on port D
-#elif defined(DUET_M) || defined(PCCB)
+#elif defined(DUET_M) || defined(PCCB) || defined(DUET3)
PIOC->PIO_ODSR = 0; // on Duet Maestro all step pins are on port C
#elif defined(DUET_06_085)
PIOD->PIO_ODSR = 0;
@@ -1340,6 +1342,8 @@ inline OutputBuffer *Platform::GetAuxGCodeReply()
PIOD->PIO_ODSR = 0;
PIOC->PIO_ODSR = 0;
PIOB->PIO_ODSR = 0;
+#elif defined(__LPC17xx__)
+ LPC_GPIO2->FIOCLR = STEP_DRIVER_MASK;
#else
# error Unknown board
#endif
diff --git a/src/RADDS/Pins_RADDS.h b/src/RADDS/Pins_RADDS.h
index 902c8e84..40a51827 100644
--- a/src/RADDS/Pins_RADDS.h
+++ b/src/RADDS/Pins_RADDS.h
@@ -37,7 +37,8 @@ const size_t DRIVES = 9;
// The number of heaters in the machine
// 0 is the heated bed even if there isn't one.
-constexpr size_t Heaters = 4;
+constexpr size_t NumEndstops = 4; // The number of inputs we have for endstops, filament sensors etc.
+constexpr size_t NumHeaters = 4;
constexpr size_t NumExtraHeaterProtections = 4; // The number of extra heater protection instances
constexpr size_t NumThermistorInputs = 4;
@@ -76,7 +77,7 @@ const Pin DIRECTION_PINS[DRIVES] = { 23, 16, 3, 60, 63, 53, 33, 27, 66 };
//
// This leaves 34, 36, and 38 as spare pins (X, Y, Z max)
-const Pin END_STOP_PINS[DRIVES] = { 28, 30, 32, 39, NoPin, NoPin, NoPin, NoPin };
+const Pin END_STOP_PINS[NumEndstops] = { 28, 30, 32, 39 };
// HEATERS - The bed is assumed to be the at index 0
@@ -88,7 +89,7 @@ const Pin TEMP_SENSE_PINS[NumThermistorInputs] = { 4, 0, 1, 2 };
// h0, h1 PMW: D13 & D12 are on TIOB0 & B8 which are both TC B channels, so they get PWM
// h2 bang-bang: D11 is on TIOA8 which is a TC A channel shared with h1, it gets bang-bang control
-const Pin HEAT_ON_PINS[Heaters] = { 7, 13, 12, 11 }; // bed, h0, h1, h2
+const Pin HEAT_ON_PINS[NumHeaters] = { 7, 13, 12, 11 }; // bed, h0, h1, h2
// Default thermistor betas
const float BED_R25 = 10000.0;
diff --git a/src/RepRap.cpp b/src/RepRap.cpp
index 6499ee16..76e18a59 100644
--- a/src/RepRap.cpp
+++ b/src/RepRap.cpp
@@ -27,6 +27,9 @@
#if HAS_HIGH_SPEED_SD
# include "sam/drivers/hsmci/hsmci.h"
# include "conf_sd_mmc.h"
+# if SAME70
+static_assert(CONF_HSMCI_XDMAC_CHANNEL == XDMAC_CHAN_HSMCI, "mismatched DMA channel assignment");
+# endif
#endif
#ifdef RTOS
@@ -715,7 +718,7 @@ void RepRap::Tick()
#endif
{
resetting = true;
- for (size_t i = 0; i < Heaters; i++)
+ for (size_t i = 0; i < NumHeaters; i++)
{
platform->SetHeater(i, 0.0);
}
@@ -1014,7 +1017,7 @@ OutputBuffer *RepRap::GetStatusResponse(uint8_t type, ResponseSource source)
// Current temperatures
response->cat("\"current\":");
ch = '[';
- for (size_t heater = 0; heater < Heaters; heater++)
+ for (size_t heater = 0; heater < NumHeaters; heater++)
{
response->catf("%c%.1f", ch, (double)heat->GetTemperature(heater));
ch = ',';
@@ -1024,7 +1027,7 @@ OutputBuffer *RepRap::GetStatusResponse(uint8_t type, ResponseSource source)
// Current states
response->cat(",\"state\":");
ch = '[';
- for (size_t heater = 0; heater < Heaters; heater++)
+ for (size_t heater = 0; heater < NumHeaters; heater++)
{
response->catf("%c%d", ch, heat->GetStatus(heater));
ch = ',';
@@ -1036,7 +1039,7 @@ OutputBuffer *RepRap::GetStatusResponse(uint8_t type, ResponseSource source)
{
response->cat(",\"names\":");
ch = '[';
- for (size_t heater = 0; heater < Heaters; heater++)
+ for (size_t heater = 0; heater < NumHeaters; heater++)
{
response->cat(ch);
ch = ',';
@@ -1197,7 +1200,7 @@ OutputBuffer *RepRap::GetStatusResponse(uint8_t type, ResponseSource source)
// Endstops
uint32_t endstops = 0;
const size_t numTotalAxes = gCodes->GetTotalAxes();
- for (size_t drive = 0; drive < DRIVES; drive++)
+ for (size_t drive = 0; drive < NumEndstops; drive++)
{
if (drive < numTotalAxes)
{
diff --git a/src/RepRapFirmware.h b/src/RepRapFirmware.h
index 5a52a2af..084265d9 100644
--- a/src/RepRapFirmware.h
+++ b/src/RepRapFirmware.h
@@ -300,7 +300,12 @@ constexpr float RadiansToDegrees = 180.0/3.141592653589793;
typedef uint32_t FilePosition;
const FilePosition noFilePosition = 0xFFFFFFFF;
+//-------------------------------------------------------------------------------------------------
// Interrupt priorities - must be chosen with care! 0 is the highest priority, 15 is the lowest.
+// This interacts with FreeRTOS config constant configLIBRARY_MAX_SYSCALL_INTERRUPT_PRIORITY which is currently defined as 5.
+// ISRs with better (numerically lower) priorities than this value cannot make FreeRTOS calls, but those interrupts wont be disabled even in FreeRTOS critical sections.
+// So use priority 4 or lower for interrupts where low latency is critical and FreeRTOS calls are not needed.
+
#if SAM4E || SAME70
const uint32_t NvicPriorityWatchdog = 0; // the secondary watchdog has the highest priority
#endif
@@ -312,22 +317,25 @@ const uint32_t NvicPriorityDriversSerialTMC = 2; // USART or UART used to contro
const uint32_t NvicPrioritySystick = 3; // systick kicks the watchdog and starts the ADC conversions, so must be quite high
#endif
-const uint32_t NvicPriorityPins = 4; // priority for GPIO pin interrupts - filament sensors must be higher than step
-
-// Currently we set configLIBRARY_MAX_SYSCALL_INTERRUPT_PRIORITY in FreeRTOS to 5.
-// This means that only interrupts with priority numerically at least 5 can make ISR-safe calls to FreeRTOS in an ISR.
-
+const uint32_t NvicPriorityPins = 5; // priority for GPIO pin interrupts - filament sensors must be higher than step
const uint32_t NvicPriorityStep = 6; // step interrupt is next highest, it can preempt most other interrupts
const uint32_t NvicPriorityWiFiUart = 7; // UART used to receive debug data from the WiFi module
const uint32_t NvicPriorityUSB = 7; // USB interrupt
const uint32_t NvicPriorityHSMCI = 7; // HSMCI command complete interrupt
#if HAS_LWIP_NETWORKING
-const uint32_t NvicPriorityNetworkTick = 8; // priority for network tick interrupt
+const uint32_t NvicPriorityNetworkTick = 8; // priority for network tick interrupt (to be replaced by a FreeRTOS task)
const uint32_t NvicPriorityEthernet = 8; // priority for Ethernet interface
#endif
const uint32_t NvicPrioritySpi = 8; // SPI is used for network transfers on Duet WiFi/Duet vEthernet
const uint32_t NvicPriorityTwi = 9; // TWI is used to read endstop and other inputs on the DueXn
+#if SAME70
+// DMA channel allocations
+const uint32_t XDMAC_CHAN_HSMCI = 0; // DMA channel used for HSMCI interface, see CONF_HSMCI_XDMAC_CHANNEL in file conf_sd_mmc.h in project CoreNG
+const uint32_t XDMAC_CHAN_TMC_TX = 1; // DMA channel for sending to SPI-controlled TMC drivers
+const uint32_t XDMAC_CHAN_TMC_RX = 2; // DMA channel for receiving from SPI-controlled TMC drivers
+#endif
+
#endif
diff --git a/src/Tools/Tool.cpp b/src/Tools/Tool.cpp
index c2622adf..64a03fb1 100644
--- a/src/Tools/Tool.cpp
+++ b/src/Tools/Tool.cpp
@@ -60,7 +60,7 @@ Tool * Tool::freelist = nullptr;
}
for (size_t i = 0; i < hCount; ++i)
{
- if (h[i] < 0 || h[i] >= (int)Heaters)
+ if (h[i] < 0 || h[i] >= (int)NumHeaters)
{
reply.copy("Tool creation: bad heater number");
return nullptr;
diff --git a/src/Tools/Tool.h b/src/Tools/Tool.h
index ba859e45..b208768d 100644
--- a/src/Tools/Tool.h
+++ b/src/Tools/Tool.h
@@ -99,8 +99,8 @@ private:
char *name;
float offset[MaxAxes];
float mix[MaxExtruders];
- float activeTemperatures[Heaters];
- float standbyTemperatures[Heaters];
+ float activeTemperatures[NumHeaters];
+ float standbyTemperatures[NumHeaters];
size_t driveCount;
size_t heaterCount;
int myNumber;
@@ -108,7 +108,7 @@ private:
AxesBitmap axisOffsetsProbed;
FansBitmap fanMapping;
uint8_t drives[MaxExtruders];
- int8_t heaters[Heaters];
+ int8_t heaters[NumHeaters];
ToolState state;
bool heaterFault;
diff --git a/src/Version.h b/src/Version.h
index 6e287564..bb45bea1 100644
--- a/src/Version.h
+++ b/src/Version.h
@@ -22,7 +22,7 @@
#endif
#ifndef DATE
-# define DATE "2018-08-22b2"
+# define DATE "2018-08-26b3"
#endif
#define AUTHORS "reprappro, dc42, chrishamm, t3p3, dnewman"