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--.cproject152
-rw-r--r--.gitignore1
-rw-r--r--src/Comms/FirmwareUpdater.cpp12
-rw-r--r--src/Comms/PanelDueUpdater.cpp2
-rw-r--r--src/Comms/PanelDueUpdater.h2
-rw-r--r--src/Config/Pins.h37
-rw-r--r--src/Config/Pins_Duet3Mini4.h498
-rw-r--r--src/Fans/LedStripDriver.cpp4
-rw-r--r--src/GCodes/GCodes2.cpp9
-rw-r--r--src/GCodes/GCodes4.cpp2
-rw-r--r--src/Hardware/SAME5x/Devices.cpp46
-rw-r--r--src/Hardware/SAME5x/same51n19a_flash_16k_bootloader.ld181
-rw-r--r--src/Heating/Sensors/CurrentLoopTemperatureSensor.cpp28
-rw-r--r--src/Heating/Sensors/CurrentLoopTemperatureSensor.h12
-rw-r--r--src/Heating/Sensors/RtdSensor31865.cpp5
-rw-r--r--src/Heating/Sensors/RtdSensor31865.h4
-rw-r--r--src/Heating/Sensors/SpiTemperatureSensor.cpp5
-rw-r--r--src/Heating/Sensors/SpiTemperatureSensor.h5
-rw-r--r--src/Heating/Sensors/TemperatureSensor.cpp2
-rw-r--r--src/Heating/Sensors/ThermocoupleSensor31855.cpp5
-rw-r--r--src/Heating/Sensors/ThermocoupleSensor31855.h4
-rw-r--r--src/Heating/Sensors/ThermocoupleSensor31856.cpp5
-rw-r--r--src/Heating/Sensors/ThermocoupleSensor31856.h4
-rw-r--r--src/Movement/DDA.cpp24
-rw-r--r--src/Movement/DDA.h12
-rw-r--r--src/Movement/DriveMovement.cpp17
-rw-r--r--src/Movement/DriveMovement.h4
-rw-r--r--src/Movement/Kinematics/FiveBarScaraKinematics.cpp5
-rw-r--r--src/Movement/Kinematics/FiveBarScaraKinematics.h4
-rw-r--r--src/Movement/Kinematics/HangprinterKinematics.cpp11
-rw-r--r--src/Movement/Kinematics/HangprinterKinematics.h4
-rw-r--r--src/Movement/Kinematics/Kinematics.cpp17
-rw-r--r--src/Movement/Kinematics/LinearDeltaKinematics.cpp4
-rw-r--r--src/Movement/Kinematics/LinearDeltaKinematics.h5
-rw-r--r--src/Movement/Kinematics/PolarKinematics.cpp4
-rw-r--r--src/Movement/Kinematics/PolarKinematics.h4
-rw-r--r--src/Movement/Kinematics/RotaryDeltaKinematics.cpp4
-rw-r--r--src/Movement/Kinematics/RotaryDeltaKinematics.h4
-rw-r--r--src/Movement/Kinematics/ScaraKinematics.cpp5
-rw-r--r--src/Movement/Kinematics/ScaraKinematics.h4
-rw-r--r--src/Movement/Move.h2
-rw-r--r--src/Platform/Platform.cpp20
-rw-r--r--src/Platform/Platform.h8
-rw-r--r--src/Version.h2
44 files changed, 1104 insertions, 85 deletions
diff --git a/.cproject b/.cproject
index 0d5426c0..b94959f9 100644
--- a/.cproject
+++ b/.cproject
@@ -1769,6 +1769,152 @@
</externalSettings>
</storageModule>
</cconfiguration>
+ <cconfiguration id="cdt.managedbuild.config.gnu.cross.exe.release.516195201.976458850.241502451.170574622.649587786.957471317.1222249630.1359583846.2076578701">
+ <storageModule buildSystemId="org.eclipse.cdt.managedbuilder.core.configurationDataProvider" id="cdt.managedbuild.config.gnu.cross.exe.release.516195201.976458850.241502451.170574622.649587786.957471317.1222249630.1359583846.2076578701" moduleId="org.eclipse.cdt.core.settings" name="Duet3Mini4">
+ <macros>
+ <stringMacro name="LinkFlags2" type="VALUE_TEXT" value="-Wl,--end-group -lm"/>
+ <stringMacro name="LinkFlags1" type="VALUE_TEXT" value="-mthumb -Wl,--cref -Wl,--check-sections -Wl,--gc-sections -Wl,--entry=Reset_Handler -Wl,--unresolved-symbols=report-all -Wl,--warn-common -Wl,--warn-section-align -Wl,--warn-unresolved-symbols -Wl,--start-group"/>
+ <stringMacro name="CoreName" type="VALUE_TEXT" value="CoreNG"/>
+ </macros>
+ <externalSettings/>
+ <extensions>
+ <extension id="org.eclipse.cdt.core.ELF" point="org.eclipse.cdt.core.BinaryParser"/>
+ <extension id="org.eclipse.cdt.core.GmakeErrorParser" point="org.eclipse.cdt.core.ErrorParser"/>
+ <extension id="org.eclipse.cdt.core.CWDLocator" point="org.eclipse.cdt.core.ErrorParser"/>
+ <extension id="org.eclipse.cdt.core.GCCErrorParser" point="org.eclipse.cdt.core.ErrorParser"/>
+ <extension id="org.eclipse.cdt.core.GASErrorParser" point="org.eclipse.cdt.core.ErrorParser"/>
+ <extension id="org.eclipse.cdt.core.GLDErrorParser" point="org.eclipse.cdt.core.ErrorParser"/>
+ </extensions>
+ </storageModule>
+ <storageModule moduleId="cdtBuildSystem" version="4.0.0">
+ <configuration artifactExtension="elf" artifactName="Duet3Firmware_Mini4" 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.170574622.649587786.957471317.1222249630.1359583846.2076578701" name="Duet3Mini4" optionalBuildProperties="org.eclipse.cdt.docker.launcher.containerbuild.property.selectedvolumes=,org.eclipse.cdt.docker.launcher.containerbuild.property.volumes=" parent="cdt.managedbuild.config.gnu.cross.exe.release" postannouncebuildStep="Generating binary file" postbuildStep="arm-none-eabi-objcopy -O binary &quot;${workspace_loc:/${ProjName}/${ConfigName}}/${BuildArtifactFileBaseName}.elf&quot; &quot;${workspace_loc:/${ProjName}/${ConfigName}}/${BuildArtifactFileBaseName}.bin&quot; &amp;&amp; crc32appender &quot;${workspace_loc:/${ProjName}/${ConfigName}}/${BuildArtifactFileBaseName}.bin&quot; &amp;&amp; python3 &quot;${workspace_loc:/${ProjName}}/Tools/uf2conv/uf2conv.py&quot; -b 0x4000 -c -o &quot;${workspace_loc:/${ProjName}/${ConfigName}}/${BuildArtifactFileBaseName}.uf2&quot; &quot;${workspace_loc:/${ProjName}/${ConfigName}}/${BuildArtifactFileBaseName}.bin&quot;">
+ <folderInfo id="cdt.managedbuild.config.gnu.cross.exe.release.516195201.976458850.241502451.170574622.649587786.957471317.1222249630.1359583846.2076578701." name="/" resourcePath="">
+ <toolChain id="cdt.managedbuild.toolchain.gnu.cross.exe.release.1609944005" name="Cross GCC" superClass="cdt.managedbuild.toolchain.gnu.cross.exe.release">
+ <option id="cdt.managedbuild.option.gnu.cross.path.1934164641" name="Path" superClass="cdt.managedbuild.option.gnu.cross.path" useByScannerDiscovery="false" value="${ArmGccPath}" valueType="string"/>
+ <option id="cdt.managedbuild.option.gnu.cross.prefix.2072003672" name="Prefix" superClass="cdt.managedbuild.option.gnu.cross.prefix" useByScannerDiscovery="false" value="arm-none-eabi-" valueType="string"/>
+ <targetPlatform archList="all" binaryParser="org.eclipse.cdt.core.ELF" id="cdt.managedbuild.targetPlatform.gnu.cross.2117575714" isAbstract="false" osList="all" superClass="cdt.managedbuild.targetPlatform.gnu.cross"/>
+ <builder buildPath="${workspace_loc:/RepRapFirmware}/Release" id="cdt.managedbuild.builder.gnu.cross.216583728" keepEnvironmentInBuildfile="false" managedBuildOn="true" name="Gnu Make Builder" parallelBuildOn="true" parallelizationNumber="optimal" superClass="cdt.managedbuild.builder.gnu.cross"/>
+ <tool id="cdt.managedbuild.tool.gnu.cross.assembler.1408450425" name="Cross GCC Assembler" superClass="cdt.managedbuild.tool.gnu.cross.assembler">
+ <option IS_BUILTIN_EMPTY="false" IS_VALUE_EMPTY="false" id="gnu.both.asm.option.include.paths.2062504226" name="Include paths (-I)" superClass="gnu.both.asm.option.include.paths" useByScannerDiscovery="false" valueType="includePath">
+ <listOptionValue builtIn="false" value="&quot;${workspace_loc:/CoreN2G}&quot;"/>
+ </option>
+ <inputType id="cdt.managedbuild.tool.gnu.assembler.input.1829834272" superClass="cdt.managedbuild.tool.gnu.assembler.input"/>
+ </tool>
+ <tool commandLinePattern="${COMMAND} ${FLAGS} ${OUTPUT_FLAG} ${OUTPUT_PREFIX}${OUTPUT} ${INPUTS}" id="cdt.managedbuild.tool.gnu.cross.c.compiler.1540056409" name="Cross GCC Compiler" superClass="cdt.managedbuild.tool.gnu.cross.c.compiler">
+ <option defaultValue="gnu.c.optimization.level.most" id="gnu.c.compiler.option.optimization.level.1285468826" name="Optimization Level" superClass="gnu.c.compiler.option.optimization.level" useByScannerDiscovery="false" value="gnu.c.optimization.level.size" valueType="enumerated"/>
+ <option id="gnu.c.compiler.option.debugging.level.1195136618" name="Debug Level" superClass="gnu.c.compiler.option.debugging.level" useByScannerDiscovery="false" value="gnu.c.debugging.level.none" valueType="enumerated"/>
+ <option id="gnu.c.compiler.option.misc.verbose.2007800042" name="Verbose (-v)" superClass="gnu.c.compiler.option.misc.verbose" useByScannerDiscovery="false" value="false" valueType="boolean"/>
+ <option id="gnu.c.compiler.option.misc.other.1096161566" name="Other flags" superClass="gnu.c.compiler.option.misc.other" useByScannerDiscovery="true" value="-c -mcpu=cortex-m4 -mthumb -mfpu=fpv4-sp-d16 -mfloat-abi=hard -mfp16-format=ieee -ffunction-sections -fdata-sections -nostdlib -Wundef -Wdouble-promotion -Werror=return-type -Werror=implicit -fsingle-precision-constant &quot;-Wa,-ahl=$*.s&quot; -fstack-usage -fdump-rtl-expand" valueType="string"/>
+ <option IS_BUILTIN_EMPTY="false" IS_VALUE_EMPTY="false" id="gnu.c.compiler.option.include.paths.221232689" name="Include paths (-I)" superClass="gnu.c.compiler.option.include.paths" useByScannerDiscovery="false" valueType="includePath">
+ <listOptionValue builtIn="false" value="&quot;${workspace_loc:/CoreN2G}&quot;"/>
+ <listOptionValue builtIn="false" value="&quot;${workspace_loc:/CoreN2G/src}&quot;"/>
+ <listOptionValue builtIn="false" value="&quot;${workspace_loc:/CoreN2G/src/SAME5x_C21/SAME5x}&quot;"/>
+ <listOptionValue builtIn="false" value="&quot;${workspace_loc:/CoreN2G/src/atmel/SAME51_DFP/1.1.139/include}&quot;"/>
+ <listOptionValue builtIn="false" value="&quot;${workspace_loc:/CoreN2G/src/arm/CMSIS/5.4.0/CMSIS/Core/Include}&quot;"/>
+ <listOptionValue builtIn="false" value="&quot;${workspace_loc:/RRFLibraries/src}&quot;"/>
+ </option>
+ <option IS_BUILTIN_EMPTY="false" IS_VALUE_EMPTY="false" id="gnu.c.compiler.option.preprocessor.def.symbols.1258371913" name="Defined symbols (-D)" superClass="gnu.c.compiler.option.preprocessor.def.symbols" useByScannerDiscovery="false" valueType="definedSymbols">
+ <listOptionValue builtIn="false" value="__SAME51N19A__"/>
+ <listOptionValue builtIn="false" value="RTOS"/>
+ <listOptionValue builtIn="false" value="DUET3MINI4"/>
+ <listOptionValue builtIn="false" value="noexcept="/>
+ </option>
+ <option id="gnu.c.compiler.option.dialect.flags.1637630414" name="Other dialect flags" superClass="gnu.c.compiler.option.dialect.flags" useByScannerDiscovery="true" value="-std=gnu99" valueType="string"/>
+ <inputType id="cdt.managedbuild.tool.gnu.c.compiler.input.158064829" superClass="cdt.managedbuild.tool.gnu.c.compiler.input"/>
+ </tool>
+ <tool id="cdt.managedbuild.tool.gnu.cross.c.linker.1016194265" name="Cross GCC Linker" superClass="cdt.managedbuild.tool.gnu.cross.c.linker"/>
+ <tool id="cdt.managedbuild.tool.gnu.cross.archiver.700027882" name="Cross GCC Archiver" superClass="cdt.managedbuild.tool.gnu.cross.archiver"/>
+ <tool command="gcc" commandLinePattern="${COMMAND} ${FLAGS} ${OUTPUT_FLAG} ${OUTPUT_PREFIX}${OUTPUT} ${LinkFlags1} ${INPUTS} ${LinkFlags2}" id="cdt.managedbuild.tool.gnu.cross.cpp.linker.1328151534" name="Cross G++ Linker" superClass="cdt.managedbuild.tool.gnu.cross.cpp.linker">
+ <option id="gnu.cpp.link.option.nostdlibs.502097497" name="No startup or default libs (-nostdlib)" superClass="gnu.cpp.link.option.nostdlibs" useByScannerDiscovery="false" value="false" valueType="boolean"/>
+ <option IS_BUILTIN_EMPTY="false" IS_VALUE_EMPTY="false" id="gnu.cpp.link.option.paths.1151296248" name="Library search path (-L)" superClass="gnu.cpp.link.option.paths" useByScannerDiscovery="false" valueType="libPaths">
+ <listOptionValue builtIn="false" value="&quot;${workspace_loc:/CANlib/SAME51_RTOS}&quot;"/>
+ <listOptionValue builtIn="false" value="&quot;${workspace_loc:/CoreN2G/SAME5x_SDHC_USB_RTOS}&quot;"/>
+ <listOptionValue builtIn="false" value="&quot;${workspace_loc:/RRFLibraries/SAME51_RTOS}&quot;"/>
+ <listOptionValue builtIn="false" value="&quot;${workspace_loc:/FreeRTOS/SAME51}&quot;"/>
+ </option>
+ <option IS_BUILTIN_EMPTY="false" IS_VALUE_EMPTY="false" id="gnu.cpp.link.option.libs.1825485573" name="Libraries (-l)" superClass="gnu.cpp.link.option.libs" useByScannerDiscovery="false" valueType="libs">
+ <listOptionValue builtIn="false" srcPrefixMapping="" srcRootPath="" value="CANlib"/>
+ <listOptionValue builtIn="false" srcPrefixMapping="" srcRootPath="" value="CoreN2G"/>
+ <listOptionValue builtIn="false" srcPrefixMapping="" srcRootPath="" value="RRFLibraries"/>
+ <listOptionValue builtIn="false" srcPrefixMapping="" srcRootPath="" value="FreeRTOS"/>
+ <listOptionValue builtIn="false" value="supc++"/>
+ </option>
+ <option id="gnu.cpp.link.option.flags.1865808730" name="Linker flags" superClass="gnu.cpp.link.option.flags" useByScannerDiscovery="false" value="--specs=nosys.specs -Os -Wl,--gc-sections -Wl,--entry=Reset_Handler -Wl,--fatal-warnings -mcpu=cortex-m4 -mfpu=fpv4-sp-d16 -mfloat-abi=hard -T&quot;${workspace_loc:/${ProjName}/src/Hardware/SAME5x/same51n19a_flash_16k_bootloader.ld}&quot; -Wl,-Map,&quot;${workspace_loc:/${ProjName}/${ConfigName}}/${BuildArtifactFileBaseName}.map&quot;" valueType="string"/>
+ <inputType id="cdt.managedbuild.tool.gnu.cpp.linker.input.1043190294" superClass="cdt.managedbuild.tool.gnu.cpp.linker.input">
+ <additionalInput kind="additionalinputdependency" paths="$(USER_OBJS)"/>
+ <additionalInput kind="additionalinput" paths="$(LIBS)"/>
+ </inputType>
+ </tool>
+ <tool command="g++" id="cdt.managedbuild.tool.gnu.cross.cpp.compiler.75143221" name="Cross G++ Compiler" superClass="cdt.managedbuild.tool.gnu.cross.cpp.compiler">
+ <option id="gnu.cpp.compiler.option.optimization.level.1923533871" name="Optimization Level" superClass="gnu.cpp.compiler.option.optimization.level" useByScannerDiscovery="false" value="gnu.cpp.compiler.optimization.level.size" valueType="enumerated"/>
+ <option id="gnu.cpp.compiler.option.debugging.level.889430722" name="Debug Level" superClass="gnu.cpp.compiler.option.debugging.level" useByScannerDiscovery="false" value="gnu.cpp.compiler.debugging.level.none" valueType="enumerated"/>
+ <option id="gnu.cpp.compiler.option.other.verbose.732401015" name="Verbose (-v)" superClass="gnu.cpp.compiler.option.other.verbose" useByScannerDiscovery="false" value="false" valueType="boolean"/>
+ <option id="gnu.cpp.compiler.option.other.other.252976821" name="Other flags" superClass="gnu.cpp.compiler.option.other.other" useByScannerDiscovery="true" value="-c -mcpu=cortex-m4 -mthumb -mfpu=fpv4-sp-d16 -mfloat-abi=hard -mfp16-format=ieee -ffunction-sections -fdata-sections -fno-threadsafe-statics -fno-rtti -fexceptions -nostdlib -Wundef -Wdouble-promotion -Werror=return-type -Wsuggest-override -fsingle-precision-constant &quot;-Wa,-ahl=$*.s&quot; -fstack-usage -fdump-rtl-expand" valueType="string"/>
+ <option IS_BUILTIN_EMPTY="false" IS_VALUE_EMPTY="false" id="gnu.cpp.compiler.option.include.paths.387492945" name="Include paths (-I)" superClass="gnu.cpp.compiler.option.include.paths" useByScannerDiscovery="false" valueType="includePath">
+ <listOptionValue builtIn="false" value="&quot;${workspace_loc:/CoreN2G}&quot;"/>
+ <listOptionValue builtIn="false" value="&quot;${workspace_loc:/FreeRTOS/src/include}&quot;"/>
+ <listOptionValue builtIn="false" value="&quot;${workspace_loc:/FreeRTOS/src/portable/GCC/ARM_CM4F}&quot;"/>
+ <listOptionValue builtIn="false" value="&quot;${workspace_loc:/${ProjName}/src}&quot;"/>
+ <listOptionValue builtIn="false" value="&quot;${workspace_loc:/${ProjName}/src/Networking}&quot;"/>
+ <listOptionValue builtIn="false" value="&quot;${workspace_loc:/${ProjName}/src/Hardware/SAME5x}&quot;"/>
+ <listOptionValue builtIn="false" value="&quot;${workspace_loc:/DuetWiFiSocketServer/src/include}&quot;"/>
+ <listOptionValue builtIn="false" value="&quot;${workspace_loc:/RRFLibraries/src}&quot;"/>
+ <listOptionValue builtIn="false" value="&quot;${workspace_loc:/CoreN2G/src}&quot;"/>
+ <listOptionValue builtIn="false" value="&quot;${workspace_loc:/CoreN2G/src/SAME5x_C21}&quot;"/>
+ <listOptionValue builtIn="false" value="&quot;${workspace_loc:/CoreN2G/src/SAME5x_C21/SAME5x}&quot;"/>
+ <listOptionValue builtIn="false" value="&quot;${workspace_loc:/CoreN2G/src/SAME5x_C21/SAME5x/hal/include}&quot;"/>
+ <listOptionValue builtIn="false" value="&quot;${workspace_loc:/CoreN2G/src/SAME5x_C21/SAME5x/hal/utils/include}&quot;"/>
+ <listOptionValue builtIn="false" value="&quot;${workspace_loc:/CoreN2G/src/SAME5x_C21/SAME5x/hri}&quot;"/>
+ <listOptionValue builtIn="false" value="&quot;${workspace_loc:/CoreN2G/src/SAME5x_C21/SAME5x/Config}&quot;"/>
+ <listOptionValue builtIn="false" value="&quot;${workspace_loc:/CoreN2G/src/atmel/SAME51_DFP/1.1.139/include}&quot;"/>
+ <listOptionValue builtIn="false" value="&quot;${workspace_loc:/CoreN2G/src/arm/CMSIS/5.4.0/CMSIS/Core/Include}&quot;"/>
+ <listOptionValue builtIn="false" value="&quot;${workspace_loc:/CANlib/src}&quot;"/>
+ </option>
+ <option IS_BUILTIN_EMPTY="false" IS_VALUE_EMPTY="false" id="gnu.cpp.compiler.option.preprocessor.def.953309493" name="Defined symbols (-D)" superClass="gnu.cpp.compiler.option.preprocessor.def" useByScannerDiscovery="false" valueType="definedSymbols">
+ <listOptionValue builtIn="false" value="__SAME51N19A__"/>
+ <listOptionValue builtIn="false" value="RTOS"/>
+ <listOptionValue builtIn="false" value="DUET3MINI4"/>
+ <listOptionValue builtIn="false" value="_XOPEN_SOURCE"/>
+ </option>
+ <option id="gnu.cpp.compiler.option.dialect.std.771691499" name="Language standard" superClass="gnu.cpp.compiler.option.dialect.std" useByScannerDiscovery="true" value="gnu.cpp.compiler.dialect.default" valueType="enumerated"/>
+ <option id="gnu.cpp.compiler.option.dialect.flags.935963924" name="Other dialect flags" superClass="gnu.cpp.compiler.option.dialect.flags" useByScannerDiscovery="true" value="-std=gnu++17" valueType="string"/>
+ <inputType id="cdt.managedbuild.tool.gnu.cpp.compiler.input.91271068" superClass="cdt.managedbuild.tool.gnu.cpp.compiler.input"/>
+ </tool>
+ </toolChain>
+ </folderInfo>
+ <sourceEntries>
+ <entry excluding="src/Hardware/SAME5x/Ethernet|src/Networking/LwipEthernet|src/Networking/LwipEthernet/Lwip/src/apps/snmp|src/Networking/LwipEthernet/Lwip/src/apps/smtp|src/Hardware/SAME70|src/DuetNG|src/Networking/LwipEthernet/Lwip/src/apps/tftp|src/Networking/W5500Ethernet|src/Networking/LwipEthernet/Lwip/src/netif/ppp|src/Networking/LwipEthernet/Lwip/src/apps/lwiperf|src/Networking/LwipEthernet/Lwip/src/apps/altcp_tls|src/Networking/LwipEthernet/Lwip/src/apps/sntp|src/Networking/LwipEthernet/Lwip/src/apps/http|src/Duet3_V06|src/Hardware/SAM4E|src/Pccb|src/Hardware/SAM4S|src/Networking/LwipEthernet/Lwip/src/apps/mqtt|src/DuetM|src/Networking/LwipEthernet/Lwip/doc" flags="VALUE_WORKSPACE_PATH|RESOLVED" kind="sourcePath" name=""/>
+ </sourceEntries>
+ </configuration>
+ </storageModule>
+ <storageModule moduleId="org.eclipse.cdt.core.externalSettings">
+ <externalSettings containerId="FreeRTOS;cdt.managedbuild.config.gnu.cross.exe.release.487753828.1418259088" factoryId="org.eclipse.cdt.core.cfg.export.settings.sipplier">
+ <externalSetting>
+ <entry flags="VALUE_WORKSPACE_PATH" kind="libraryPath" name="/FreeRTOS/SAME51"/>
+ <entry flags="RESOLVED" kind="libraryFile" name="FreeRTOS" srcPrefixMapping="" srcRootPath=""/>
+ </externalSetting>
+ </externalSettings>
+ <externalSettings containerId="RRFLibraries;cdt.managedbuild.config.gnu.cross.lib.release.1693990866.1129583112" factoryId="org.eclipse.cdt.core.cfg.export.settings.sipplier">
+ <externalSetting>
+ <entry flags="VALUE_WORKSPACE_PATH" kind="libraryPath" name="/RRFLibraries/SAME51_RTOS"/>
+ <entry flags="RESOLVED" kind="libraryFile" name="RRFLibraries" srcPrefixMapping="" srcRootPath=""/>
+ </externalSetting>
+ </externalSettings>
+ <externalSettings containerId="CoreN2G;cdt.managedbuild.config.gnu.cross.lib.release.675522878.1031364120.1670975982" factoryId="org.eclipse.cdt.core.cfg.export.settings.sipplier">
+ <externalSetting>
+ <entry flags="VALUE_WORKSPACE_PATH" kind="includePath" name="/CoreN2G"/>
+ <entry flags="VALUE_WORKSPACE_PATH" kind="libraryPath" name="/CoreN2G/SAME5x_SDHC_USB_RTOS"/>
+ <entry flags="RESOLVED" kind="libraryFile" name="CoreN2G" srcPrefixMapping="" srcRootPath=""/>
+ </externalSetting>
+ </externalSettings>
+ <externalSettings containerId="CANlib;cdt.managedbuild.config.gnu.cross.lib.release.1485070058.881130662" factoryId="org.eclipse.cdt.core.cfg.export.settings.sipplier">
+ <externalSetting>
+ <entry flags="VALUE_WORKSPACE_PATH" kind="libraryPath" name="/CANlib/SAME51_RTOS"/>
+ <entry flags="RESOLVED" kind="libraryFile" name="CANlib" srcPrefixMapping="" srcRootPath=""/>
+ </externalSetting>
+ </externalSettings>
+ </storageModule>
+ </cconfiguration>
</storageModule>
<storageModule moduleId="cdtBuildSystem" version="4.0.0">
<project id="RepRapFirmware.cdt.managedbuild.target.gnu.cross.exe.1494358155" name="Executable" projectType="cdt.managedbuild.target.gnu.cross.exe"/>
@@ -1847,6 +1993,9 @@
<scannerConfigBuildInfo instanceId="cdt.managedbuild.config.gnu.cross.exe.release.516195201.976458850.241502451.1275216290.274082366.1645191116.1852610203.289083307.712841925.1685260958;cdt.managedbuild.config.gnu.cross.exe.release.516195201.976458850.241502451.1275216290.274082366.1645191116.1852610203.289083307.712841925.1685260958.;cdt.managedbuild.tool.gnu.cross.cpp.compiler.715778553;cdt.managedbuild.tool.gnu.cpp.compiler.input.2089527705">
<autodiscovery enabled="true" problemReportingEnabled="true" selectedProfileId=""/>
</scannerConfigBuildInfo>
+ <scannerConfigBuildInfo instanceId="cdt.managedbuild.config.gnu.cross.exe.release.516195201.976458850.241502451.170574622.649587786.957471317.1222249630.1359583846.2076578701;cdt.managedbuild.config.gnu.cross.exe.release.516195201.976458850.241502451.170574622.649587786.957471317.1222249630.1359583846.2076578701.;cdt.managedbuild.tool.gnu.cross.cpp.compiler.75143221;cdt.managedbuild.tool.gnu.cpp.compiler.input.91271068">
+ <autodiscovery enabled="true" problemReportingEnabled="true" selectedProfileId=""/>
+ </scannerConfigBuildInfo>
<scannerConfigBuildInfo instanceId="cdt.managedbuild.config.gnu.cross.exe.release.516195201.976458850.1027429289;cdt.managedbuild.config.gnu.cross.exe.release.516195201.976458850.1027429289.;cdt.managedbuild.tool.gnu.cross.c.compiler.764246283;cdt.managedbuild.tool.gnu.c.compiler.input.110609707">
<autodiscovery enabled="true" problemReportingEnabled="true" selectedProfileId=""/>
</scannerConfigBuildInfo>
@@ -1874,6 +2023,9 @@
<scannerConfigBuildInfo instanceId="cdt.managedbuild.config.gnu.cross.exe.release.516195201.976458850.241502451.170574622.649587786.957471317.1222249630;cdt.managedbuild.config.gnu.cross.exe.release.516195201.976458850.241502451.170574622.649587786.957471317.1222249630.;cdt.managedbuild.tool.gnu.cross.c.compiler.1595573667;cdt.managedbuild.tool.gnu.c.compiler.input.733744821">
<autodiscovery enabled="true" problemReportingEnabled="true" selectedProfileId=""/>
</scannerConfigBuildInfo>
+ <scannerConfigBuildInfo instanceId="cdt.managedbuild.config.gnu.cross.exe.release.516195201.976458850.241502451.170574622.649587786.957471317.1222249630.1359583846.2076578701;cdt.managedbuild.config.gnu.cross.exe.release.516195201.976458850.241502451.170574622.649587786.957471317.1222249630.1359583846.2076578701.;cdt.managedbuild.tool.gnu.cross.c.compiler.1540056409;cdt.managedbuild.tool.gnu.c.compiler.input.158064829">
+ <autodiscovery enabled="true" problemReportingEnabled="true" selectedProfileId=""/>
+ </scannerConfigBuildInfo>
<scannerConfigBuildInfo instanceId="cdt.managedbuild.config.gnu.cross.exe.release.516195201.976458850.241502451.170574622.649587786.957471317;cdt.managedbuild.config.gnu.cross.exe.release.516195201.976458850.241502451.170574622.649587786.957471317.;cdt.managedbuild.tool.gnu.cross.cpp.compiler.628323987;cdt.managedbuild.tool.gnu.cpp.compiler.input.612052200">
<autodiscovery enabled="true" problemReportingEnabled="true" selectedProfileId=""/>
</scannerConfigBuildInfo>
diff --git a/.gitignore b/.gitignore
index 3cdac429..9da06738 100644
--- a/.gitignore
+++ b/.gitignore
@@ -18,3 +18,4 @@
/Duet3_MB6XD/
/Duet3_CAN0/
/Duet3_Debug/
+/Duet3Mini4/
diff --git a/src/Comms/FirmwareUpdater.cpp b/src/Comms/FirmwareUpdater.cpp
index 32f0d7e4..84597db2 100644
--- a/src/Comms/FirmwareUpdater.cpp
+++ b/src/Comms/FirmwareUpdater.cpp
@@ -87,7 +87,7 @@ namespace FirmwareUpdater
return false;
}
#endif
-#if HAS_AUX_DEVICES
+#if SUPPORT_PANELDUE_FLASH
PanelDueUpdater * const panelDueUpdater = reprap.GetPlatform().GetPanelDueUpdater();
if (panelDueUpdater != nullptr && !panelDueUpdater->Idle())
{
@@ -99,14 +99,13 @@ namespace FirmwareUpdater
void UpdateModule(unsigned int module, const size_t serialChannel, const StringRef& filenameRef) noexcept
{
-#if HAS_WIFI_NETWORKING || HAS_AUX_DEVICES
- Platform& platform = reprap.GetPlatform();
+#if HAS_WIFI_NETWORKING || SUPPORT_PANELDUE_FLASH
switch(module)
{
# if HAS_WIFI_NETWORKING
case WifiExternalFirmwareModule:
# ifdef DUET_NG
- if (platform.IsDuetWiFi())
+ if (reprap.GetPlatform().IsDuetWiFi())
# endif
{
reprap.GetNetwork().ResetWiFiForUpload(true);
@@ -115,7 +114,7 @@ namespace FirmwareUpdater
case WifiFirmwareModule:
# ifdef DUET_NG
- if (platform.IsDuetWiFi())
+ if (reprap.GetPlatform().IsDuetWiFi())
# endif
{
WifiFirmwareUploader * const uploader = reprap.GetNetwork().GetWifiUploader();
@@ -127,9 +126,10 @@ namespace FirmwareUpdater
}
break;
# endif
-# if HAS_AUX_DEVICES
+# if SUPPORT_PANELDUE_FLASH
case PanelDueFirmwareModule:
{
+ Platform& platform = reprap.GetPlatform();
if (platform.GetPanelDueUpdater() == nullptr)
{
platform.InitPanelDueUpdater();
diff --git a/src/Comms/PanelDueUpdater.cpp b/src/Comms/PanelDueUpdater.cpp
index 92c5989c..bd381e6d 100644
--- a/src/Comms/PanelDueUpdater.cpp
+++ b/src/Comms/PanelDueUpdater.cpp
@@ -7,7 +7,7 @@
#include "PanelDueUpdater.h"
-#if HAS_AUX_DEVICES
+#if SUPPORT_PANELDUE_FLASH
#include <Platform/Platform.h>
#include <Platform/RepRap.h>
diff --git a/src/Comms/PanelDueUpdater.h b/src/Comms/PanelDueUpdater.h
index f7589d16..bb814371 100644
--- a/src/Comms/PanelDueUpdater.h
+++ b/src/Comms/PanelDueUpdater.h
@@ -10,7 +10,7 @@
#include <RepRapFirmware.h>
-#if HAS_AUX_DEVICES
+#if SUPPORT_PANELDUE_FLASH
#include <General/NamedEnum.h>
diff --git a/src/Config/Pins.h b/src/Config/Pins.h
index 3646403b..9cef26ef 100644
--- a/src/Config/Pins.h
+++ b/src/Config/Pins.h
@@ -23,6 +23,9 @@
# elif defined(DUET3MINI_V04)
# define DUET3MINI 1
# define PLATFORM Duet3Mini
+# elif defined(DUET3MINI4)
+# define DUET3MINI 1
+# define PLATFORM Duet3Mini4
# elif defined(__LPC17xx__)
# define PLATFORM LPC
# else
@@ -69,8 +72,16 @@
# define SUPPORT_LED_STRIPS 0
#endif
+#ifndef SUPPORT_SPI_SENSORS
+# define SUPPORT_SPI_SENSORS 1
+#endif
+
#define HAS_AUX_DEVICES (defined(SERIAL_AUX_DEVICE)) // if SERIAL_AUX_DEVICE is defined then we have one or more aux devices
+#ifndef SUPPORT_PANELDUE_FLASH
+# define SUPPORT_PANELDUE_FLASH HAS_AUX_DEVICES
+#endif
+
#ifndef ALLOW_ARBITRARY_PANELDUE_PORT
# define ALLOW_ARBITRARY_PANELDUE_PORT (0)
#endif
@@ -207,6 +218,31 @@
# define SUPPORT_ACCELEROMETERS 0
#endif
+// Optional kinematics support, to allow us to reduce flash memory usage
+#ifndef SUPPORT_LINEAR_DELTA
+# define SUPPORT_LINEAR_DELTA 1
+#endif
+
+#ifndef SUPPORT_ROTARY_DELTA
+# define SUPPORT_ROTARY_DELTA 1
+#endif
+
+#ifndef SUPPORT_POLAR
+# define SUPPORT_POLAR 1
+#endif
+
+#ifndef SUPPORT_SCARA
+# define SUPPORT_SCARA 1
+#endif
+
+#ifndef SUPPORT_FIVEBARSCARA
+# define SUPPORT_FIVEBARSCARA 1
+#endif
+
+#ifndef SUPPORT_HANGPRINTER
+# define SUPPORT_HANGPRINTER 1
+#endif
+
// We must define MCU_HAS_UNIQUE_ID as either 0 or 1 so we can use it in maths
#if SAM4E || SAM4S || SAME70 || SAME5x
# define MCU_HAS_UNIQUE_ID 1
@@ -221,7 +257,6 @@
#endif
// Define SUPPORT_REMOTE_COMMANDS according to whether this hardware accepts commands over CAN
-// For now we exclude Duet 3 MB6HC because CoreNG doesn't support analog callbacks
#define SUPPORT_REMOTE_COMMANDS (SUPPORT_CAN_EXPANSION && !defined(DUET3_ATE))
#define USE_REMOTE_INPUT_SHAPING (0) //TODO temporary!!!
diff --git a/src/Config/Pins_Duet3Mini4.h b/src/Config/Pins_Duet3Mini4.h
new file mode 100644
index 00000000..d59551b4
--- /dev/null
+++ b/src/Config/Pins_Duet3Mini4.h
@@ -0,0 +1,498 @@
+/*
+ * Pins_Duet3Mini4.h
+ *
+ * Created on: 02 Feb 2022
+ * Author: David
+ */
+
+#ifndef SRC_DUET3MINI_PINS_DUET3MINI_H_
+#define SRC_DUET3MINI_PINS_DUET3MINI_H_
+
+#include <PinDescription.h>
+
+#define DEFAULT_BOARD_TYPE BoardType::Duet3Mini4
+
+#define BOARD_SHORT_NAME "Mini4"
+#define BOARD_NAME "Duet 3 Mini 4"
+#define FIRMWARE_NAME "RepRapFirmware for Duet 3 Mini 4"
+
+#define IAP_FIRMWARE_FILE "Duet3Firmware_" BOARD_SHORT_NAME ".uf2"
+#define IAP_UPDATE_FILE "Duet3_SDiap32_" BOARD_SHORT_NAME ".bin"
+constexpr uint32_t IAP_IMAGE_START = 0x20028000;
+
+#define WIFI_FIRMWARE_FILE "DuetWiFiServer.bin"
+
+// Features definition
+#define HAS_LWIP_NETWORKING 0
+#define HAS_WIFI_NETWORKING 1
+#define HAS_W5500_NETWORKING 0
+#define HAS_SBC_INTERFACE 0
+
+#define HAS_MASS_STORAGE 1
+#define HAS_HIGH_SPEED_SD 1
+//#define HAS_CPU_TEMP_SENSOR 0 // according to the SAME5x errata doc, the temperature sensors don't work in revision A or D chips (revision D is latest as at 2020-06-28)
+#define HAS_CPU_TEMP_SENSOR 1 // enable this as an experiment - it may be better than nothing
+
+#define SUPPORT_TMC22xx 1
+#define HAS_STALL_DETECT 1
+
+#define HAS_VOLTAGE_MONITOR 1
+#define ENFORCE_MAX_VIN 0
+#define HAS_VREF_MONITOR 1
+
+#define SUPPORT_CAN_EXPANSION 0
+
+#define SUPPORT_LED_STRIPS 1
+#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_LASER 1 // support laser cutters and engravers using G1 S parameter
+#define SUPPORT_IOBITS 0 // set to support P parameter in G0/G1 commands
+#define SUPPORT_DHT_SENSOR 1 // set nonzero to support DHT temperature/humidity sensors (requires RTOS)
+#define SUPPORT_WORKPLACE_COORDINATES 1 // set nonzero to support G10 L2 and G53..59
+#define SUPPORT_12864_LCD 1 // set nonzero to support 12864 LCD and rotary encoder
+#define SUPPORT_ACCELEROMETERS 1
+#define SUPPORT_OBJECT_MODEL 1
+#define SUPPORT_FTP 0
+#define SUPPORT_TELNET 0
+#define SUPPORT_ASYNC_MOVES 0
+#define ALLOCATE_DEFAULT_PORTS 0
+#define TRACK_OBJECT_NAMES 1
+#define SUPPORT_PANELDUE_FLASH 0
+#define SUPPORT_SPI_SENSORS 0
+
+#define USE_CACHE 1 // set nonzero to enable the cache
+#define USE_MPU 0 // set nonzero to enable the memory protection unit
+
+// Disable the kinematcs we don't need to save flash memory space
+#define SUPPORT_LINEAR_DELTA 0
+#define SUPPORT_ROTARY_DELTA 0
+#define SUPPORT_POLAR 0
+#define SUPPORT_SCARA 0
+#define SUPPORT_FIVEBARSCARA 0
+#define SUPPORT_HANGPRINTER 0
+
+// The physical capabilities of the machine
+
+#include <Duet3Common.h>
+
+constexpr size_t NumDirectDrivers = 4; // The maximum number of drives supported by the electronics
+
+constexpr size_t MaxSmartDrivers = NumDirectDrivers; // The maximum number of smart drivers
+
+constexpr size_t MaxPortsPerHeater = 2;
+
+constexpr size_t MaxBedHeaters = 4;
+constexpr size_t MaxChamberHeaters = 4;
+constexpr int8_t DefaultE0Heater = 1; // Index of the default first extruder heater, used only for the legacy status response
+
+constexpr size_t NumThermistorInputs = 3;
+constexpr size_t NumTmcDriversSenseChannels = 2;
+
+constexpr size_t MinAxes = 3; // The minimum and default number of axes
+constexpr size_t MaxAxes = 10; // The maximum number of movement axes in the machine
+constexpr size_t MaxDriversPerAxis = 4; // The maximum number of stepper drivers assigned to one axis
+
+constexpr size_t MaxExtruders = 8; // The maximum number of extruders
+constexpr size_t MaxAxesPlusExtruders = 12;
+
+constexpr size_t MaxHeatersPerTool = 2;
+constexpr size_t MaxExtrudersPerTool = 8;
+
+constexpr unsigned int MaxTriggers = 16; // Maximum number of triggers
+
+constexpr size_t NumSerialChannels = 3; // The number of serial IO channels (USB and two auxiliary UARTs)
+
+#define SERIAL_MAIN_DEVICE (serialUSB)
+#define SERIAL_AUX_DEVICE (serialUart0)
+#define SERIAL_AUX2_DEVICE (serialUart1)
+
+// SerialUSB
+constexpr Pin UsbVBusPin = PortBPin(6); // Pin used to monitor VBUS on USB port
+
+//#define I2C_IFACE Wire // First and only I2C interface
+//#define I2C_IRQn WIRE_ISR_ID
+
+// The numbers of entries in each array must correspond with the values of DRIVES, AXES, or HEATERS. Set values to NoPin to flag unavailability.
+
+// Drivers
+constexpr Pin GlobalTmc22xxEnablePin = PortCPin(28); // The pin that drives ENN of all drivers
+PortGroup * const StepPio = &(PORT->Group[2]); // The PIO that all the step pins are on (port C)
+
+constexpr Pin STEP_PINS[NumDirectDrivers] = { PortCPin(26), PortCPin(25), PortCPin(24), PortCPin(19) };
+constexpr Pin DIRECTION_PINS[NumDirectDrivers] = { PortBPin(3), PortBPin(29), PortBPin(28), PortDPin(20) };
+constexpr Pin DriverDiagPins[NumDirectDrivers] = { PortAPin(10), PortBPin(8), PortAPin(22), PortAPin(23) };
+// CCL inputs that the DIAG inputs use. Bits 0-1 are the CCL LUT number. Bits 8-19 are the value to OR in to the control register for that LUT.
+constexpr uint32_t CclDiagInputs[NumDirectDrivers] =
+{
+ 0x01 | CCL_LUTCTRL_INSEL2(0x04), // CCLIN[5] = 1.2
+ 0x02 | CCL_LUTCTRL_INSEL2(0x04), // CCLIN[8] = 2.2
+ 0x02 | CCL_LUTCTRL_INSEL0(0x04), // CCLIN[6] = 2.0
+ 0x02 | CCL_LUTCTRL_INSEL1(0x04), // CCLIN[7] = 2.1
+};
+
+// UART interface to stepper drivers
+constexpr uint8_t TMC22xxSercomNumber = 1;
+Sercom * const SERCOM_TMC22xx = SERCOM1;
+constexpr IRQn TMC22xx_SERCOM_IRQn = SERCOM1_0_IRQn;
+constexpr Pin TMC22xxSercomTxPin = PortAPin(0);
+constexpr GpioPinFunction TMC22xxSercomTxPinPeriphMode = GpioPinFunction::D;
+constexpr Pin TMC22xxSercomRxPin = PortAPin(1);
+constexpr GpioPinFunction TMC22xxSercomRxPinPeriphMode = GpioPinFunction::D;
+constexpr uint8_t TMC22xxSercomRxPad = 1;
+constexpr Pin TMC22xxMuxPins[1] = { PortDPin(0) };
+
+#define TMC22xx_HAS_ENABLE_PINS 0
+#define TMC22xx_HAS_MUX 0
+#define TMC22xx_USES_SERCOM 1
+#define TMC22xx_VARIABLE_NUM_DRIVERS 0
+#define TMC22xx_SINGLE_DRIVER 0
+#define TMC22xx_USE_SLAVEADDR 1
+#define TMC22xx_DEFAULT_STEALTHCHOP 0
+
+// Define the baud rate used to send/receive data to/from the drivers.
+// If we assume a worst case clock frequency of 8MHz then the maximum baud rate is 8MHz/16 = 500kbaud.
+// We send data via a 1K series resistor. Even if we assume a 200pF load on the shared UART line, this gives a 200ns time constant, which is much less than the 2us bit time @ 500kbaud.
+// To write a register we need to send 12 bytes and receive 8 bytes after a programmable delay. To read a register we send 4 bytes and receive 8 bytes after a programmable delay.
+// In testing I found that 500kbaud was not reliable. Minimum baud rate is 9000.
+constexpr uint32_t DriversBaudRate = 100000; // at 100kbaud a transfer may take up to 2ms
+constexpr uint32_t TransferTimeout = 6; // any transfer should complete within 6 ticks @ 1ms/tick. 5 wasn't quite enough.
+constexpr uint32_t DefaultStandstillCurrentPercent = 75;
+constexpr float DriverSenseResistor = 0.056 + 0.02; // in ohms
+
+constexpr float DriverVRef = 180.0; // in mV
+constexpr float DriverFullScaleCurrent = DriverVRef/DriverSenseResistor; // in mA
+constexpr float DriverCsMultiplier = 32.0/DriverFullScaleCurrent;
+constexpr float MaximumMotorCurrent = 2000.0;
+constexpr float MaximumStandstillCurrent = 1500.0;
+
+// Thermistors
+constexpr Pin TEMP_SENSE_PINS[NumThermistorInputs] = { PortCPin(0), PortCPin(1), PortCPin(2) }; // Thermistor pin numbers
+constexpr Pin VssaSensePin = PortBPin(4);
+constexpr Pin VrefSensePin = PortBPin(5);
+
+constexpr float DefaultThermistorSeriesR = 2200.0; // Thermistor series resistor value in ohms
+constexpr float MinVrefLoadR = (DefaultThermistorSeriesR / NumThermistorInputs) * 4700.0/((DefaultThermistorSeriesR / NumThermistorInputs) + 4700.0);
+ // there are 3 temperature sensing channels and a 4K7 load resistor
+constexpr float VrefSeriesR = 27.0;
+
+// Digital pins that SPi devices have their select lines tied to
+constexpr Pin SpiTempSensorCsPins[] = { PortDPin(11), PortCPin(7) }; // SPI0_CS1, SPI0_CS2
+
+// Analogue pin numbers
+constexpr Pin PowerMonitorVinDetectPin = PortCPin(3); // Vin monitor
+constexpr float PowerMonitorVoltageRange = 11.0 * 3.3; // We use an 11:1 voltage divider
+
+#ifdef DEBUG
+constexpr Pin DiagPin = NoPin; // Diag/status LED pin is shared with SWD
+constexpr Pin ActLedPin = NoPin; // Activity LED pin is shared with SWCLK
+#else
+constexpr Pin DiagPin = PortAPin(31); // Diag/status LED pin
+constexpr Pin ActLedPin = PortAPin(30); // Activity LED pin (Ethernet Yellow LED on v0.2 board)
+#endif
+
+constexpr bool DiagOnPolarity = false;
+constexpr bool ActOnPolarity = false;
+
+// SD cards
+constexpr size_t NumSdCards = 2;
+constexpr Pin SdCardDetectPins[NumSdCards] = { PortBPin(16), PortDPin(12) };
+
+constexpr Pin SdWriteProtectPins[NumSdCards] = { NoPin, NoPin };
+constexpr Pin SdSpiCSPins[NumSdCards - 1] = { PortCPin(14) };
+constexpr Pin SdMciPins[] = { PortAPin(20), PortAPin(21), PortBPin(18), PortBPin(19), PortBPin(20), PortBPin(21) };
+constexpr GpioPinFunction SdMciPinsFunction = GpioPinFunction::I;
+Sdhc * const SdDevice = SDHC0;
+constexpr IRQn_Type SdhcIRQn = SDHC0_IRQn;
+constexpr uint32_t ExpectedSdCardSpeed = 15000000;
+
+// 12864 LCD
+// The ST7920 datasheet specifies minimum clock cycle time 400ns @ Vdd=4.5V, min. clock width 200ns high and 20ns low.
+// This assumes that the Vih specification is met, which is 0.7 * Vcc = 3.5V @ Vcc=5V
+// The Duet Maestro level shifts all 3 LCD signals to 5V, so we meet the Vih specification and can reliably run at 2MHz.
+// For other electronics, there are reports that operation with 3.3V LCD signals may work if you reduce the clock frequency.
+// The ST7567 specifies minimum clock cycle time 50ns i.e. 20MHz @ Vcc=3.3V
+constexpr uint32_t LcdSpiClockFrequency = 2000000; // 2.0MHz
+constexpr Pin LcdCSPin = PortCPin(6);
+constexpr Pin EncoderPinA = PortCPin(11);
+constexpr Pin EncoderPinB = PortDPin(1);
+constexpr Pin EncoderPinSw = PortBPin(9);
+
+constexpr Pin LcdA0Pin = PortAPin(2);
+constexpr Pin LcdBeepPin = PortAPin(9);
+
+// Neopixel output
+constexpr Pin NeopixelOutPin = PortAPin(8);
+constexpr GpioPinFunction NeopixelOutPinFunction = GpioPinFunction::H; // QSPI Data[0]
+#define LEDSTRIP_USES_USART (0)
+
+// Shared SPI definitions
+constexpr uint8_t SharedSpiSercomNumber = 7;
+constexpr Pin SharedSpiMosiPin = PortCPin(12);
+constexpr Pin SharedSpiMisoPin = PortCPin(15);
+constexpr Pin SharedSpiSclkPin = PortCPin(13);
+constexpr GpioPinFunction SharedSpiPinFunction = GpioPinFunction::C;
+
+// Serial on IO0
+constexpr uint8_t Serial0SercomNumber = 2;
+constexpr uint8_t Sercom0RxPad = 1;
+#define SERIAL0_ISR0 SERCOM2_0_Handler
+#define SERIAL0_ISR1 SERCOM2_1_Handler
+#define SERIAL0_ISR2 SERCOM2_2_Handler
+#define SERIAL0_ISR3 SERCOM2_3_Handler
+
+constexpr Pin Serial0TxPin = PortBPin(25);
+constexpr Pin Serial0RxPin = PortBPin(24);
+constexpr GpioPinFunction Serial0PinFunction = GpioPinFunction::D;
+
+// Serial on IO1
+constexpr uint8_t Serial1SercomNumber = 5;
+constexpr uint8_t Sercom1RxPad = 1;
+#define SERIAL1_ISR0 SERCOM5_0_Handler
+#define SERIAL1_ISR1 SERCOM5_1_Handler
+#define SERIAL1_ISR2 SERCOM5_2_Handler
+#define SERIAL1_ISR3 SERCOM5_3_Handler
+
+constexpr Pin Serial1TxPin = PortBPin(31);
+constexpr Pin Serial1RxPin = PortBPin(30);
+constexpr GpioPinFunction Serial1PinFunction = GpioPinFunction::D;
+
+// WiFi pins
+constexpr unsigned int WiFiUartSercomNumber = 3;
+constexpr uint8_t WiFiUartRxPad = 1;
+constexpr Pin WiFiUartSercomPins[] = { PortAPin(16), PortAPin(17) };
+constexpr GpioPinFunction WiFiUartSercomPinsMode = GpioPinFunction::D;
+constexpr IRQn WiFiUartSercomIRQn = SERCOM3_0_IRQn; // this is the first of 4 interrupt numbers
+#define SERIAL_WIFI_ISR0 SERCOM3_0_Handler
+#define SERIAL_WIFI_ISR1 SERCOM3_1_Handler
+#define SERIAL_WIFI_ISR2 SERCOM3_2_Handler
+#define SERIAL_WIFI_ISR3 SERCOM3_3_Handler
+
+constexpr unsigned int WiFiSpiSercomNumber = 4;
+Sercom * const WiFiSpiSercom = SERCOM4;
+constexpr Pin EspMosiPin = PortAPin(15);
+constexpr Pin EspMisoPin = PortAPin(13);
+constexpr Pin EspSclkPin = PortAPin(12);
+constexpr Pin EspSSPin = PortAPin(14);
+constexpr Pin WiFiSpiSercomPins[] = { EspSclkPin, EspMisoPin, EspSSPin, EspMosiPin };
+constexpr GpioPinFunction WiFiSpiSercomPinsMode = GpioPinFunction::D;
+constexpr IRQn WiFiSpiSercomIRQn = SERCOM4_3_IRQn; // this is the SS Low interrupt, the only one we use
+#define ESP_SPI_HANDLER SERCOM4_3_Handler
+
+constexpr Pin EspResetPin = PortCPin(17);
+constexpr Pin EspEnablePin = PortCPin(20);
+constexpr Pin EspDataReadyPin = PortAPin(18);
+constexpr Pin SamTfrReadyPin = PortAPin(19);
+constexpr Pin SamCsPin = PortAPin(14);
+
+// Function to look up a pin name and pass back the corresponding index into the pin table
+bool LookupPinName(const char *pn, LogicalPin& lpin, bool& hardwareInverted) noexcept;
+
+// List of assignable pins and their mapping from names to MPU ports. This is indexed by logical pin number.
+// The names must match user input that has been concerted to lowercase and had _ and - characters stripped out.
+// Aliases are separate by the , character.
+// If a pin name is prefixed by ! then this means the pin is hardware inverted. The same pin may have names for both the inverted and non-inverted cases,
+// for example the inverted heater pins on the expansion connector are available as non-inverted servo pins on a DueX.
+
+constexpr PinDescription PinTable[] =
+{
+ // TC TCC ADC SERCOM in SERCOM out Exint Capability PinNames
+ // Port A
+ { TcOutput::none, TccOutput::none, AdcInput::none, SercomIo::none, SercomIo::none, Nx, PinCapability::none, nullptr }, // PA00 TMC UART TxD
+ { TcOutput::none, TccOutput::none, AdcInput::none, SercomIo::none, SercomIo::none, Nx, PinCapability::none, nullptr }, // PA01 TMC UART RxD
+ { TcOutput::none, TccOutput::none, AdcInput::none, SercomIo::none, SercomIo::none, Nx, PinCapability::none, "ate.lcd.a0" }, // PA02 LCD A0
+ { TcOutput::none, TccOutput::none, AdcInput::none, SercomIo::none, SercomIo::none, Nx, PinCapability::none, "ate.sbc.dr" }, // PA03 SBC data ready
+ { TcOutput::none, TccOutput::none, AdcInput::none, SercomIo::none, SercomIo::none, Nx, PinCapability::none, nullptr }, // PA04 SBC SPI MISO
+ { TcOutput::none, TccOutput::none, AdcInput::none, SercomIo::none, SercomIo::none, Nx, PinCapability::none, nullptr }, // PA05 SBC SPI SCLK
+ { TcOutput::none, TccOutput::none, AdcInput::none, SercomIo::none, SercomIo::none, Nx, PinCapability::none, nullptr }, // PA06 SBC SPI SS
+ { TcOutput::none, TccOutput::none, AdcInput::none, SercomIo::none, SercomIo::none, Nx, PinCapability::none, nullptr }, // PA07 SBC SPI MOSI
+ { TcOutput::none, TccOutput::none, AdcInput::none, SercomIo::none, SercomIo::none, Nx, PinCapability::none, nullptr }, // PA08 Neopixel output (QSPI MOSI)
+ { TcOutput::tc0_1, TccOutput::none, AdcInput::none, SercomIo::none, SercomIo::none, Nx, PinCapability::none, "are.lcd.buzz" }, // PA09 LCD buzzer
+ { TcOutput::none, TccOutput::none, AdcInput::none, SercomIo::none, SercomIo::none, Nx, PinCapability::none, "ate.d0.diag" }, // PA10 driver 0 diag
+ { TcOutput::tc1_1, TccOutput::none, AdcInput::none, SercomIo::none, SercomIo::none, Nx, PinCapability::wpwm, "out4" }, // PA11 OUT4
+ { TcOutput::none, TccOutput::none, AdcInput::none, SercomIo::none, SercomIo::none, Nx, PinCapability::none, nullptr }, // PA12 Ethernet/WiFi SCLK (SERCOM4.1)
+ { TcOutput::none, TccOutput::none, AdcInput::none, SercomIo::none, SercomIo::none, Nx, PinCapability::none, nullptr }, // PA13 Ethernet/WiFi MISO (SERCOM4.0)
+ { TcOutput::none, TccOutput::none, AdcInput::none, SercomIo::none, SercomIo::none, Nx, PinCapability::none, nullptr }, // PA14 Ethernet/WiFi SS (SERCOM4.2)
+ { TcOutput::none, TccOutput::none, AdcInput::none, SercomIo::none, SercomIo::none, Nx, PinCapability::none, nullptr }, // PA15 Ethernet/WiFi MOSI (SERCOM4.3)
+ { TcOutput::none, TccOutput::none, AdcInput::none, SercomIo::none, SercomIo::none, Nx, PinCapability::none, nullptr }, // PA16 Ethernet GCLK2 out/WiFi RxD (SERCOM3.1)
+ { TcOutput::none, TccOutput::none, AdcInput::none, SercomIo::none, SercomIo::none, Nx, PinCapability::none, nullptr }, // PA17 Ethernet/WiFi TxD (SERCOM3.0)
+ { TcOutput::none, TccOutput::none, AdcInput::none, SercomIo::none, SercomIo::none, 2, PinCapability::none, nullptr }, // PA18 Ethernet/WiFi ESP_DATA_RDY
+ { TcOutput::none, TccOutput::none, AdcInput::none, SercomIo::none, SercomIo::none, Nx, PinCapability::none, nullptr }, // PA19 Ethernet/WiFi SAM_TRANSFER_RDY
+ { TcOutput::none, TccOutput::none, AdcInput::none, SercomIo::none, SercomIo::none, Nx, PinCapability::none, nullptr }, // PA20 SDHC CMD
+ { TcOutput::none, TccOutput::none, AdcInput::none, SercomIo::none, SercomIo::none, Nx, PinCapability::none, nullptr }, // PA21 SDHC CLK
+ { TcOutput::none, TccOutput::none, AdcInput::none, SercomIo::none, SercomIo::none, Nx, PinCapability::none, "ate.d2.diag" }, // PA22 driver 2 diag
+ { TcOutput::none, TccOutput::none, AdcInput::none, SercomIo::none, SercomIo::none, Nx, PinCapability::none, "ate.d3.diag" }, // PA23 driver 3 diag
+ { TcOutput::none, TccOutput::none, AdcInput::none, SercomIo::none, SercomIo::none, Nx, PinCapability::none, nullptr }, // PA24 USB
+ { TcOutput::none, TccOutput::none, AdcInput::none, SercomIo::none, SercomIo::none, Nx, PinCapability::none, nullptr }, // PA25 USB
+ { TcOutput::none, TccOutput::none, AdcInput::none, SercomIo::none, SercomIo::none, Nx, PinCapability::none, nullptr }, // PA26 not on chip
+ { TcOutput::none, TccOutput::none, AdcInput::none, SercomIo::none, SercomIo::none, Nx, PinCapability::none, "ate.d6.dir" }, // PA27 driver 6 dir
+ { TcOutput::none, TccOutput::none, AdcInput::none, SercomIo::none, SercomIo::none, Nx, PinCapability::none, nullptr }, // PA28 not on chip
+ { TcOutput::none, TccOutput::none, AdcInput::none, SercomIo::none, SercomIo::none, Nx, PinCapability::none, nullptr }, // PA29 not on chip
+ { TcOutput::none, TccOutput::none, AdcInput::none, SercomIo::none, SercomIo::none, Nx, PinCapability::none, nullptr }, // PA30 swclk/ACT LED
+ { TcOutput::none, TccOutput::none, AdcInput::none, SercomIo::none, SercomIo::none, Nx, PinCapability::none, nullptr }, // PA31 swdio/STATUS LED
+
+ // Port B
+ { TcOutput::none, TccOutput::none, AdcInput::none, SercomIo::none, SercomIo::none, Nx, PinCapability::none, "ate.d5.dir" }, // PB00 driver 5 dir
+ { TcOutput::tc7_1, TccOutput::none, AdcInput::none, SercomIo::none, SercomIo::none, Nx, PinCapability::wpwm, "out6,laser,vfd" }, // PB01 OUT6
+ { TcOutput::none, TccOutput::tcc2_2F, AdcInput::none, SercomIo::none, SercomIo::none, Nx, PinCapability::wpwm, "out5" }, // PB02 OUT5
+ { TcOutput::none, TccOutput::none, AdcInput::none, SercomIo::none, SercomIo::none, Nx, PinCapability::none, "ate.d0.dir" }, // PB03 driver 0 dir
+ { TcOutput::none, TccOutput::none, AdcInput::adc1_6, SercomIo::none, SercomIo::none, Nx, PinCapability::none, nullptr }, // PB04 VssaMon
+ { TcOutput::none, TccOutput::none, AdcInput::adc1_7, SercomIo::none, SercomIo::none, Nx, PinCapability::none, nullptr }, // PB05 VrefMon
+ { TcOutput::none, TccOutput::none, AdcInput::adc1_8, SercomIo::none, SercomIo::none, 6, PinCapability::none, "ate.vbus" }, // PB06 Vbus
+ { TcOutput::none, TccOutput::none, AdcInput::adc1_9, SercomIo::none, SercomIo::none, 7, PinCapability::ainr, "io3.in" }, // PB07 IO3_IN
+ { TcOutput::none, TccOutput::none, AdcInput::none, SercomIo::none, SercomIo::none, Nx, PinCapability::none, "ate.d1.diag" }, // PB08 driver 1 diag
+ { TcOutput::none, TccOutput::none, AdcInput::none, SercomIo::none, SercomIo::none, 9, PinCapability::none, "ate.enc.sw" }, // PB09 ENC SW
+ { TcOutput::none, TccOutput::none, AdcInput::none, SercomIo::none, SercomIo::none, Nx, PinCapability::none, "ate.d5.diag" }, // PB10 driver 5 diag
+ { TcOutput::tc5_1, TccOutput::none, AdcInput::none, SercomIo::none, SercomIo::none, Nx, PinCapability::wpwm, "out3" }, // PB11 OUT3
+ { TcOutput::none, TccOutput::tcc3_0F, AdcInput::none, SercomIo::none, SercomIo::none, Nx, PinCapability::wpwm, "io3.out" }, // PB12 IO3_OUT
+ { TcOutput::tc4_1, TccOutput::none, AdcInput::none, SercomIo::none, SercomIo::none, Nx, PinCapability::wpwm, "out2" }, // PB13 OUT2
+ { TcOutput::none, TccOutput::none, AdcInput::none, SercomIo::none, SercomIo::none, Nx, PinCapability::wpwm, nullptr }, // PB14 CAN Tx
+ { TcOutput::none, TccOutput::none, AdcInput::none, SercomIo::none, SercomIo::none, Nx, PinCapability::read, nullptr }, // PB15 CAN Rx
+ { TcOutput::none, TccOutput::none, AdcInput::none, SercomIo::none, SercomIo::none, Nx, PinCapability::none, "ate.cd" }, // PB16 SD CD
+ { TcOutput::tc6_1, TccOutput::none, AdcInput::none, SercomIo::none, SercomIo::none, Nx, PinCapability::wpwm, "out0" }, // PB17 OUT0
+ { TcOutput::none, TccOutput::none, AdcInput::none, SercomIo::none, SercomIo::none, Nx, PinCapability::none, nullptr }, // PB18 SD DAT0
+ { TcOutput::none, TccOutput::none, AdcInput::none, SercomIo::none, SercomIo::none, Nx, PinCapability::none, nullptr }, // PB19 SD DAT1
+ { TcOutput::none, TccOutput::none, AdcInput::none, SercomIo::none, SercomIo::none , Nx, PinCapability::none, nullptr }, // PB20 SD DAT2
+ { TcOutput::none, TccOutput::none, AdcInput::none, SercomIo::none, SercomIo::none, Nx, PinCapability::none, nullptr }, // PB21 SD DAT3
+ { TcOutput::none, TccOutput::none, AdcInput::none, SercomIo::none, SercomIo::none, Nx, PinCapability::none, nullptr }, // PB22 crystal XIN1
+ { TcOutput::none, TccOutput::none, AdcInput::none, SercomIo::none, SercomIo::none, Nx, PinCapability::none, nullptr }, // PB23 crystal XOUT1
+ { TcOutput::none, TccOutput::none, AdcInput::none, SercomIo::sercom2d, SercomIo::none, 8, PinCapability::read, "io0.in" }, // PB24 IO0_IN
+ { TcOutput::none, TccOutput::none, AdcInput::none, SercomIo::none, SercomIo::sercom2d, Nx, PinCapability::write, "io0.out" }, // PB25 IO0_OUT
+ { TcOutput::none, TccOutput::none, AdcInput::none, SercomIo::none, SercomIo::none, 12, PinCapability::read, "out4.tach" }, // PB26 OUT4 tacho
+ { TcOutput::none, TccOutput::none, AdcInput::none, SercomIo::none, SercomIo::none, 13, PinCapability::read, "out3.tach" }, // PB27 OUT3 tacho
+ { TcOutput::none, TccOutput::none, AdcInput::none, SercomIo::none, SercomIo::none, Nx, PinCapability::none, "ate.d2.dir" }, // PB28 driver 2 dir
+ { TcOutput::none, TccOutput::none, AdcInput::none, SercomIo::none, SercomIo::none, Nx, PinCapability::none, "ate.d1.dir" }, // PB29 driver 1 dir
+ { TcOutput::none, TccOutput::none, AdcInput::none, SercomIo::sercom5d, SercomIo::none, 14, PinCapability::read, "io1.in" }, // PB30 IO1_IN
+ { TcOutput::none, TccOutput::tcc0_7G, AdcInput::none, SercomIo::none, SercomIo::sercom5d, Nx, PinCapability::wpwm, "io1.out" }, // PB31 IO1_OUT
+
+ // Port C
+ { TcOutput::none, TccOutput::none, AdcInput::adc1_10, SercomIo::none, SercomIo::none, Nx, PinCapability::ain, "temp0" }, // PC00 thermistor0
+ { TcOutput::none, TccOutput::none, AdcInput::adc1_11, SercomIo::none, SercomIo::none, Nx, PinCapability::ain, "temp1" }, // PC01 thermistor1
+ { TcOutput::none, TccOutput::none, AdcInput::adc1_4, SercomIo::none, SercomIo::none, Nx, PinCapability::ain, "temp2" }, // PC02 thermistor2
+ { TcOutput::none, TccOutput::none, AdcInput::adc1_5, SercomIo::none, SercomIo::none, Nx, PinCapability::none, "ate.vin" }, // PC03 VIN monitor
+ { TcOutput::none, TccOutput::none, AdcInput::none, SercomIo::none, SercomIo::none, 4, PinCapability::read, "io5.in" }, // PC04 IO5_IN
+ { TcOutput::none, TccOutput::none, AdcInput::none, SercomIo::none, SercomIo::none, 5, PinCapability::read, "io4.in" }, // PC05 IO4_IN
+ { TcOutput::none, TccOutput::none, AdcInput::none, SercomIo::none, SercomIo::none, Nx, PinCapability::write, "spi.cs3" }, // PC06 SPI_CS3
+ { TcOutput::none, TccOutput::none, AdcInput::none, SercomIo::none, SercomIo::none, Nx, PinCapability::write, "spi.cs2" }, // PC07 SPI CS2
+ { TcOutput::none, TccOutput::none, AdcInput::none, SercomIo::none, SercomIo::none, Nx, PinCapability::none, nullptr }, // PC08 not on chip
+ { TcOutput::none, TccOutput::none, AdcInput::none, SercomIo::none, SercomIo::none, Nx, PinCapability::none, nullptr }, // PC09 not on chip
+ { TcOutput::none, TccOutput::tcc1_4G, AdcInput::none, SercomIo::none, SercomIo::none, Nx, PinCapability::wpwm, "out1" }, // PC10 OUT1
+ { TcOutput::none, TccOutput::none, AdcInput::none, SercomIo::none, SercomIo::none, 11, PinCapability::none, "ate.enc.a" }, // PC11 ENC A
+ { TcOutput::none, TccOutput::none, AdcInput::none, SercomIo::none, SercomIo::none, Nx, PinCapability::none, nullptr }, // PC12 SPI MOSI
+ { TcOutput::none, TccOutput::none, AdcInput::none, SercomIo::none, SercomIo::none, Nx, PinCapability::none, nullptr }, // PC13 SPI SCK
+ { TcOutput::none, TccOutput::none, AdcInput::none, SercomIo::none, SercomIo::none, Nx, PinCapability::none, nullptr }, // PC14 SPI CS0 (external SD card)
+ { TcOutput::none, TccOutput::none, AdcInput::none, SercomIo::none, SercomIo::none, Nx, PinCapability::none, nullptr }, // PC15 SPI_MISO
+ { TcOutput::none, TccOutput::none, AdcInput::none, SercomIo::none, SercomIo::none, Nx, PinCapability::none, "ate.d4.step" }, // PC16 driver4 step
+ { TcOutput::none, TccOutput::none, AdcInput::none, SercomIo::none, SercomIo::none, Nx, PinCapability::none, nullptr }, // PC17 phy reset/ESP reset
+ { TcOutput::none, TccOutput::none, AdcInput::none, SercomIo::none, SercomIo::none, Nx, PinCapability::none, "ate.d6.step" }, // PC18 driver 6 step
+ { TcOutput::none, TccOutput::none, AdcInput::none, SercomIo::none, SercomIo::none, Nx, PinCapability::none, "ate.d3.step" }, // PC19 driver 3 step
+ { TcOutput::none, TccOutput::none, AdcInput::none, SercomIo::none, SercomIo::none, Nx, PinCapability::none, nullptr }, // PC20 Ethernet/WiFi ESP_EN
+ { TcOutput::none, TccOutput::none, AdcInput::none, SercomIo::none, SercomIo::none, Nx, PinCapability::none, "ate.d6.diag" }, // PC21 driver 4 diag
+ { TcOutput::none, TccOutput::none, AdcInput::none, SercomIo::none, SercomIo::none, Nx, PinCapability::none, nullptr }, // PC22 Ethernet
+ { TcOutput::none, TccOutput::none, AdcInput::none, SercomIo::none, SercomIo::none, Nx, PinCapability::none, nullptr }, // PC23 Ethernet
+ { TcOutput::none, TccOutput::none, AdcInput::none, SercomIo::none, SercomIo::none, Nx, PinCapability::none, "ate.d2.step" }, // PC24 driver2 step
+ { TcOutput::none, TccOutput::none, AdcInput::none, SercomIo::none, SercomIo::none, Nx, PinCapability::none, "ate.d1.step" }, // PC25 driver1 step
+ { TcOutput::none, TccOutput::none, AdcInput::none, SercomIo::none, SercomIo::none, Nx, PinCapability::none, "ate.d0.step" }, // PC26 driver0 step
+ { TcOutput::none, TccOutput::none, AdcInput::none, SercomIo::none, SercomIo::none, Nx, PinCapability::none, "ate.d6.diag" }, // PC27 driver 6 diag
+ { TcOutput::none, TccOutput::none, AdcInput::none, SercomIo::none, SercomIo::none, Nx, PinCapability::none, nullptr }, // PC28 driver ENN
+ { TcOutput::none, TccOutput::none, AdcInput::none, SercomIo::none, SercomIo::none, Nx, PinCapability::none, nullptr }, // PC29 not on chip
+ { TcOutput::none, TccOutput::none, AdcInput::none, SercomIo::none, SercomIo::none, Nx, PinCapability::none, "ate.d5.step" }, // PC30 driver 5 step
+ { TcOutput::none, TccOutput::none, AdcInput::adc1_13, SercomIo::none, SercomIo::none, 15, PinCapability::ainr, "io6.in" }, // PC31 IO6_IN
+
+ // Port D
+ { TcOutput::none, TccOutput::none, AdcInput::none, SercomIo::none, SercomIo::none, Nx, PinCapability::none, nullptr }, // PD00 drivers UART mux
+ { TcOutput::none, TccOutput::none, AdcInput::none, SercomIo::none, SercomIo::none, 1, PinCapability::none, "ate.enc.b" }, // PD01 ENC B
+ { TcOutput::none, TccOutput::none, AdcInput::none, SercomIo::none, SercomIo::none, Nx, PinCapability::none, nullptr }, // PD02 not on chip
+ { TcOutput::none, TccOutput::none, AdcInput::none, SercomIo::none, SercomIo::none, Nx, PinCapability::none, nullptr }, // PD03 not on chip
+ { TcOutput::none, TccOutput::none, AdcInput::none, SercomIo::none, SercomIo::none, Nx, PinCapability::none, nullptr }, // PD04 not on chip
+ { TcOutput::none, TccOutput::none, AdcInput::none, SercomIo::none, SercomIo::none, Nx, PinCapability::none, nullptr }, // PD05 not on chip
+ { TcOutput::none, TccOutput::none, AdcInput::none, SercomIo::none, SercomIo::none, Nx, PinCapability::none, nullptr }, // PD06 not on chip
+ { TcOutput::none, TccOutput::none, AdcInput::none, SercomIo::none, SercomIo::none, Nx, PinCapability::none, nullptr }, // PD07 not on chip
+ { TcOutput::none, TccOutput::none, AdcInput::none, SercomIo::sercom6d, SercomIo::none, 3, PinCapability::read, "io2.in" }, // PD08 IO2_IN
+ { TcOutput::none, TccOutput::tcc0_2F, AdcInput::none, SercomIo::none, SercomIo::sercom6d, Nx, PinCapability::write, "io2.out" }, // PD09 IO2_OUT
+ { TcOutput::none, TccOutput::none, AdcInput::none, SercomIo::none, SercomIo::none, Nx, PinCapability::write, "io4.out,pson" }, // PD10 IO4_OUT and PS_ON
+ { TcOutput::none, TccOutput::none, AdcInput::none, SercomIo::none, SercomIo::none, Nx, PinCapability::write, "spi.cs1" }, // PD11 SPI2 CS1
+ { TcOutput::none, TccOutput::none, AdcInput::none, SercomIo::none, SercomIo::none, 7, PinCapability::read , "ate.spi2.cd" }, // PD12 SPI2_CD
+
+#if 1
+ // Port D 13-19 are not on the chip
+ // Port D 20-21 are driver 3 dir and driver 4 dir but those don't need to be in the pin table
+#else
+ { TcOutput::none, TccOutput::none, AdcInput::none, SercomIo::none, SercomIo::none, Nx, nullptr }, // PD13 not on chip
+ { TcOutput::none, TccOutput::none, AdcInput::none, SercomIo::none, SercomIo::none, Nx, nullptr }, // PD14 not on chip
+ { TcOutput::none, TccOutput::none, AdcInput::none, SercomIo::none, SercomIo::none, Nx, nullptr }, // PD15 not on chip
+ { TcOutput::none, TccOutput::none, AdcInput::none, SercomIo::none, SercomIo::none, Nx, nullptr }, // PD16 not on chip
+ { TcOutput::none, TccOutput::none, AdcInput::none, SercomIo::none, SercomIo::none, Nx, nullptr }, // PD17 not on chip
+ { TcOutput::none, TccOutput::none, AdcInput::none, SercomIo::none, SercomIo::none, Nx, nullptr }, // PD18 not on chip
+ { TcOutput::none, TccOutput::none, AdcInput::none, SercomIo::none, SercomIo::none, Nx, nullptr }, // PD19 not on chip
+ { TcOutput::none, TccOutput::none, AdcInput::none, SercomIo::none, SercomIo::none, Nx, nullptr }, // PD20 driver6 dir
+ { TcOutput::none, TccOutput::none, AdcInput::none, SercomIo::none, SercomIo::none, Nx, nullptr }, // PD21 driver5 dir
+#endif
+};
+
+constexpr unsigned int NumNamedPins = ARRAY_SIZE(PinTable);
+static_assert(NumNamedPins == 32+32+32+13);
+
+// DMA channel assignments. Channels 0-3 have individual interrupt vectors, channels 4-31 share an interrupt vector.
+// When static arbitration within a priority level is selected, lower channel number have higher priority.
+// So we use the low channel numbers for the highest priority sources.
+constexpr DmaChannel DmacChanSbcTx = 0;
+constexpr DmaChannel DmacChanSbcRx = 1;
+constexpr DmaChannel DmacChanWiFiTx = 2;
+constexpr DmaChannel DmacChanWiFiRx = 3;
+constexpr DmaChannel DmacChanDotStarTx = 4;
+constexpr DmaChannel DmacChanTmcTx = 5;
+constexpr DmaChannel DmacChanTmcRx = 6;
+
+constexpr unsigned int NumDmaChannelsUsed = 7;
+
+// The DMAC has priority levels 0-3 but on revision A chips it is unsafe to use multiple levels
+// Fortunately, all our SAME54P20Achips seem to be revision D
+constexpr DmaPriority DmacPrioTmcTx = 0;
+constexpr DmaPriority DmacPrioTmcRx = 1; // the baud rate is 100kbps so this is not very critical
+constexpr DmaPriority DmacPrioWiFi = 2; // high speed SPI in slave mode
+constexpr DmaPriority DmacPrioSbc = 2; // high speed SPI in slave mode
+constexpr DmaPriority DmacPrioDotStar = 1; // QSPI in master mode
+
+// Timer allocation
+// TC2 and TC3 are used for step pulse generation and software timers
+TcCount32 * const StepTc = &(TC2->COUNT32);
+constexpr IRQn StepTcIRQn = TC2_IRQn;
+constexpr unsigned int StepTcNumber = 2;
+#define STEP_TC_HANDLER TC2_Handler
+
+// SAME5x event channel allocation, max 32 channels. Only the first 12 provide a synchronous or resynchronised path and can generate interrupts.
+
+constexpr EventNumber CclLut0Event = 0; // this uses up 4 channels
+constexpr EventNumber NextFreeEvent = CclLut0Event + 4;
+
+// Step pulse generation
+namespace StepPins
+{
+ // *** These next three functions must use the same bit assignments in the drivers bitmap ***
+ // Each stepper driver must be assigned one bit in a 32-bit word, in such a way that multiple drivers can be stepped efficiently
+ // and more or less simultaneously by doing parallel writes to several bits in one or more output ports.
+ // All our step pins are on port C, so the bitmap is just the map of step bits in port C.
+
+ // Calculate the step bit for a driver. This doesn't need to be fast. It must return 0 if the driver is remote.
+ static inline uint32_t CalcDriverBitmap(size_t driver) noexcept
+ {
+ return (driver < NumDirectDrivers)
+ ? 1u << (STEP_PINS[driver] & 0x1Fu)
+ : 0;
+ }
+
+ // Set the specified step pins high. This needs to be fast.
+ static inline __attribute__((always_inline)) void StepDriversHigh(uint32_t driverMap) noexcept
+ {
+ StepPio->OUTSET.reg = driverMap; // all step pins are on port C
+ }
+
+ // Set the specified step pins low. This needs to be fast.
+ static inline void __attribute__((always_inline)) StepDriversLow(uint32_t driverMap) noexcept
+ {
+ StepPio->OUTCLR.reg = driverMap; // all step pins are on port C
+ }
+}
+
+#endif /* SRC_DUET3MINI_PINS_DUET3MINI_H_ */
diff --git a/src/Fans/LedStripDriver.cpp b/src/Fans/LedStripDriver.cpp
index 3b790f1d..ccb6ae35 100644
--- a/src/Fans/LedStripDriver.cpp
+++ b/src/Fans/LedStripDriver.cpp
@@ -5,7 +5,7 @@
* Author: David
*/
-#include <Fans/LedStripDriver.h>
+#include "LedStripDriver.h"
#if SUPPORT_LED_STRIPS
@@ -17,7 +17,7 @@
// Define which types of LED strip this hardware supports
#define SUPPORT_DMA_NEOPIXEL (defined(DUET3_MB6HC) || defined(DUET3_MB6XD) || defined(DUET3MINI) || defined(PCCB_10))
#define SUPPORT_DMA_DOTSTAR (defined(DUET3_MB6HC) || defined(DUET3_MB6XD) || defined(PCCB_10))
-#define SUPPORT_BITBANG_NEOPIXEL (defined(DUET3MINI) || defined(DUET_NG))
+#define SUPPORT_BITBANG_NEOPIXEL (defined(DUET3MINI_V04) || defined(DUET_NG))
#if SUPPORT_DMA_NEOPIXEL || SUPPORT_DMA_DOTSTAR
diff --git a/src/GCodes/GCodes2.cpp b/src/GCodes/GCodes2.cpp
index 91afae7e..cb42348e 100644
--- a/src/GCodes/GCodes2.cpp
+++ b/src/GCodes/GCodes2.cpp
@@ -3506,12 +3506,7 @@ bool GCodes::HandleMcode(GCodeBuffer& gb, const StringRef& reply) THROWS(GCodeEx
result = reprap.GetMove().ConfigurePressureAdvance(gb, reply);
break;
- case 573: // Report heater average PWM
- {
- const unsigned int heater = gb.GetLimitedUIValue('P', MaxHeaters);
- reply.printf("Average heater %u PWM: %.3f", heater, (double)reprap.GetHeat().GetAveragePWM(heater));
- }
- break;
+ // case 573 was report heater average PWM but is no longer supported because you can use "echo heat/heaters[N].avgPwm" instead
case 574: // Set endstop configuration
// We may be about to delete endstops, so make sure we are not executing a move that uses them
@@ -4600,7 +4595,7 @@ bool GCodes::HandleMcode(GCodeBuffer& gb, const StringRef& reply) THROWS(GCodeEx
}
}
#endif
-#if HAS_AUX_DEVICES
+#if SUPPORT_PANELDUE_FLASH
if (gb.Seen('A'))
{
const uint32_t serialChannel = gb.GetLimitedUIValue('A', 1, NumSerialChannels);
diff --git a/src/GCodes/GCodes4.cpp b/src/GCodes/GCodes4.cpp
index fe89f463..1170bcc3 100644
--- a/src/GCodes/GCodes4.cpp
+++ b/src/GCodes/GCodes4.cpp
@@ -562,7 +562,7 @@ void GCodes::RunStateMachine(GCodeBuffer& gb, const StringRef& reply) noexcept
gb.SetState(GCodeState::flashing2);
}
}
-# if HAS_AUX_DEVICES
+# if SUPPORT_PANELDUE_FLASH
else
{
PanelDueUpdater* const panelDueUpdater = platform.GetPanelDueUpdater();
diff --git a/src/Hardware/SAME5x/Devices.cpp b/src/Hardware/SAME5x/Devices.cpp
index a8114cca..dc78165d 100644
--- a/src/Hardware/SAME5x/Devices.cpp
+++ b/src/Hardware/SAME5x/Devices.cpp
@@ -111,55 +111,31 @@ static void UsbInit() noexcept
static void SdhcInit() noexcept
{
// Set up SDHC clock
+#if defined(DUET3MINI_V04)
+ // Using SDHC 1
hri_mclk_set_AHBMASK_SDHC1_bit(MCLK);
hri_gclk_write_PCHCTRL_reg(GCLK, SDHC1_GCLK_ID, GCLK_PCHCTRL_GEN(GclkNum90MHz) | GCLK_PCHCTRL_CHEN);
hri_gclk_write_PCHCTRL_reg(GCLK, SDHC1_GCLK_ID_SLOW, GCLK_PCHCTRL_GEN(GclkNum31KHz) | GCLK_PCHCTRL_CHEN);
-
- // Set up SDHC pins
-#if 1
- // This is the code generated by Atmel Start. I don't know whether it is all necessary.
- gpio_set_pin_direction(PortAPin(21), GPIO_DIRECTION_OUT);
- gpio_set_pin_level(PortAPin(21), false);
- gpio_set_pin_pull_mode(PortAPin(21), GPIO_PULL_OFF);
- gpio_set_pin_function(PortAPin(21), PINMUX_PA21I_SDHC1_SDCK);
-
- gpio_set_pin_direction(PortAPin(20), GPIO_DIRECTION_OUT);
- gpio_set_pin_level(PortAPin(20), false);
- gpio_set_pin_pull_mode(PortAPin(20), GPIO_PULL_OFF);
- gpio_set_pin_function(PortAPin(20), PINMUX_PA20I_SDHC1_SDCMD);
-
- gpio_set_pin_direction(PortBPin(18), GPIO_DIRECTION_OUT);
- gpio_set_pin_level(PortBPin(18), false);
- gpio_set_pin_pull_mode(PortBPin(18), GPIO_PULL_OFF);
- gpio_set_pin_function(PortBPin(18), PINMUX_PB18I_SDHC1_SDDAT0);
-
- gpio_set_pin_direction(PortBPin(19), GPIO_DIRECTION_OUT);
- gpio_set_pin_level(PortBPin(19), false);
- gpio_set_pin_pull_mode(PortBPin(19), GPIO_PULL_OFF);
- gpio_set_pin_function(PortBPin(19), PINMUX_PB19I_SDHC1_SDDAT1);
-
- gpio_set_pin_direction(PortBPin(20), GPIO_DIRECTION_OUT);
- gpio_set_pin_level(PortBPin(20), false);
- gpio_set_pin_pull_mode(PortBPin(20), GPIO_PULL_OFF);
- gpio_set_pin_function(PortBPin(20), PINMUX_PB20I_SDHC1_SDDAT2);
-
- gpio_set_pin_direction(PortBPin(21), GPIO_DIRECTION_OUT);
- gpio_set_pin_level(PortBPin(21), false);
- gpio_set_pin_pull_mode(PortBPin(21), GPIO_PULL_OFF);
- gpio_set_pin_function(PortBPin(21), PINMUX_PB21I_SDHC1_SDDAT3);
+#elif defined(DUET3MINI4)
+ // Using SDHC 0
+ hri_mclk_set_AHBMASK_SDHC0_bit(MCLK);
+ hri_gclk_write_PCHCTRL_reg(GCLK, SDHC0_GCLK_ID, GCLK_PCHCTRL_GEN(GclkNum90MHz) | GCLK_PCHCTRL_CHEN);
+ hri_gclk_write_PCHCTRL_reg(GCLK, SDHC0_GCLK_ID_SLOW, GCLK_PCHCTRL_GEN(GclkNum31KHz) | GCLK_PCHCTRL_CHEN);
#else
+# error Unknown board
+#endif
+
// Setup SD card interface pins
for (Pin p : SdMciPins)
{
SetPinFunction(p, SdMciPinsFunction);
}
-#endif
}
void DeviceInit() noexcept
{
// Ensure the Ethernet PHY or WiFi module is held reset
- pinMode(EthernetPhyResetPin, OUTPUT_LOW);
+ pinMode(EspResetPin, OUTPUT_LOW);
UsbInit();
SdhcInit();
diff --git a/src/Hardware/SAME5x/same51n19a_flash_16k_bootloader.ld b/src/Hardware/SAME5x/same51n19a_flash_16k_bootloader.ld
new file mode 100644
index 00000000..b5b0f6f8
--- /dev/null
+++ b/src/Hardware/SAME5x/same51n19a_flash_16k_bootloader.ld
@@ -0,0 +1,181 @@
+/**
+ * \file
+ *
+ * \brief Linker script for running in internal FLASH on the SAME51N19A
+ *
+ * Copyright (c) 2019 Microchip Technology Inc.
+ *
+ * \asf_license_start
+ *
+ * \page License
+ *
+ * SPDX-License-Identifier: Apache-2.0
+ *
+ * Licensed under the Apache License, Version 2.0 (the "License"); you may
+ * not use this file except in compliance with the License.
+ * You may obtain a copy of the Licence at
+ *
+ * http://www.apache.org/licenses/LICENSE-2.0
+ *
+ * Unless required by applicable law or agreed to in writing, software
+ * distributed under the License is distributed on an AS IS BASIS, WITHOUT
+ * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+ * See the License for the specific language governing permissions and
+ * limitations under the License.
+ *
+ * \asf_license_stop
+ *
+ */
+
+
+OUTPUT_FORMAT("elf32-littlearm", "elf32-littlearm", "elf32-littlearm")
+OUTPUT_ARCH(arm)
+SEARCH_DIR(.)
+
+/* Memory Spaces Definitions */
+MEMORY
+{
+ rom (rx) : ORIGIN = 0x00004000, LENGTH = 0x0007c000
+ ram (rwx) : ORIGIN = 0x20000000, LENGTH = 0x00030000
+ bkupram (rwx) : ORIGIN = 0x47000000, LENGTH = 0x00002000
+ qspi (rwx) : ORIGIN = 0x04000000, LENGTH = 0x01000000
+}
+
+/* Section Definitions */
+SECTIONS
+{
+ .text :
+ {
+ . = ALIGN(4);
+ _sfixed = .;
+ KEEP(*(.vectors .vectors.*))
+ *(.text .text.* .gnu.linkonce.t.*)
+ *(.glue_7t) *(.glue_7)
+ *(.rodata .rodata* .gnu.linkonce.r.*)
+
+ /* Support C constructors, and C destructors in both user code
+ and the C library. This also provides support for C++ code. */
+ . = ALIGN(4);
+ KEEP(*(.init))
+ . = ALIGN(4);
+ __preinit_array_start = .;
+ KEEP (*(.preinit_array))
+ __preinit_array_end = .;
+
+ . = ALIGN(4);
+ __init_array_start = .;
+ KEEP (*(SORT(.init_array.*)))
+ KEEP (*(.init_array))
+ __init_array_end = .;
+
+ . = ALIGN(4);
+ KEEP (*crtbegin.o(.ctors))
+ KEEP (*(EXCLUDE_FILE (*crtend.o) .ctors))
+ KEEP (*(SORT(.ctors.*)))
+ KEEP (*crtend.o(.ctors))
+
+ . = ALIGN(4);
+ KEEP(*(.fini))
+
+ . = ALIGN(4);
+ __fini_array_start = .;
+ KEEP (*(.fini_array))
+ KEEP (*(SORT(.fini_array.*)))
+ __fini_array_end = .;
+
+ KEEP (*crtbegin.o(.dtors))
+ KEEP (*(EXCLUDE_FILE (*crtend.o) .dtors))
+ KEEP (*(SORT(.dtors.*)))
+ KEEP (*crtend.o(.dtors))
+
+ . = ALIGN(4);
+ _efixed = .; /* End of text section */
+ } > rom
+
+ .ARM.extab :
+ {
+ *(.ARM.extab* .gnu.linkonce.armextab.*)
+ } > rom
+
+ /* .ARM.exidx is sorted, so has to go in its own output section. */
+ PROVIDE_HIDDEN (__exidx_start = .);
+ .ARM.exidx :
+ {
+ *(.ARM.exidx* .gnu.linkonce.armexidx.*)
+ } > rom
+ PROVIDE_HIDDEN (__exidx_end = .);
+
+ . = ALIGN(4);
+ _etext = .;
+
+ /* CAN message buffers must be in the first 64K of RAM */
+ .canMessage (NOLOAD) :
+ {
+ . = ALIGN(4);
+ _sCanMessage = . ;
+ *(.CanMessage .CanMessage.*)
+ . = ALIGN(4);
+ _eCanMessage = . ;
+ } > ram
+
+ .relocate : AT (_etext)
+ {
+ . = ALIGN(4);
+ _srelocate = .;
+ *(.ramfunc .ramfunc.*);
+ *(.data .data.*);
+ . = ALIGN(4);
+ _erelocate = .;
+ } > ram
+
+ _firmware_end = _etext + (_erelocate - _srelocate); /* Embedded files start here */
+ _firmware_crc = _firmware_end; /* We append the CRC32 to the binary file. This is its offset in memory if we don't append embedded files */
+
+ /* .bss section which is used for uninitialized data */
+ .bss ALIGN(16) (NOLOAD) :
+ {
+ _sbss = . ;
+ _szero = .;
+ *(.bss .bss.*)
+ *(COMMON)
+ . = ALIGN(4);
+ _ebss = . ;
+ _ezero = .;
+ } > ram
+
+ . = ALIGN(4);
+ _end = . ;
+
+ /* .stack_dummy section doesn't contains any symbols. It is only
+ used for linker to calculate size of stack sections, and assign
+ values to stack symbols later */
+ .stack_dummy :
+ {
+ *(.stack*)
+ } > ram
+
+ .bkupram (NOLOAD):
+ {
+ . = ALIGN(8);
+ _sbkupram = .;
+ *(.bkupram .bkupram.*);
+ . = ALIGN(8);
+ _ebkupram = .;
+ } > bkupram
+
+ .qspi (NOLOAD):
+ {
+ . = ALIGN(8);
+ _sqspi = .;
+ *(.qspi .qspi.*);
+ . = ALIGN(8);
+ _eqspi = .;
+ } > qspi
+
+ /* Set stack top to end of ram, and stack limit move down by
+ * size of stack_dummy section */
+ __StackTop = ORIGIN(ram) + LENGTH(ram);
+ __StackLimit = __StackTop - SIZEOF(.stack_dummy);
+ PROVIDE(_sstack = __StackLimit);
+ PROVIDE(_estack = __StackTop);
+}
diff --git a/src/Heating/Sensors/CurrentLoopTemperatureSensor.cpp b/src/Heating/Sensors/CurrentLoopTemperatureSensor.cpp
index 5b0be7f1..24100285 100644
--- a/src/Heating/Sensors/CurrentLoopTemperatureSensor.cpp
+++ b/src/Heating/Sensors/CurrentLoopTemperatureSensor.cpp
@@ -6,10 +6,17 @@
*/
#include "CurrentLoopTemperatureSensor.h"
+
+#if SUPPORT_SPI_SENSORS
+
#include <Platform/RepRap.h>
#include <Platform/Platform.h>
#include <GCodes/GCodeBuffer/GCodeBuffer.h>
+#if SUPPORT_REMOTE_COMMANDS
+# include <CanMessageGenericParser.h>
+#endif
+
const uint32_t MCP3204_Frequency = 1000000; // maximum for MCP3204 is 1MHz @ 2.7V, will be slightly higher at 3.3V
// The MCP3204 samples input data on the rising edge and changes the output data on the rising edge.
@@ -38,7 +45,26 @@ GCodeResult CurrentLoopTemperatureSensor::Configure(GCodeBuffer& gb, const Strin
gb.TryGetUIValue('C', chipChannel, changed);
gb.TryGetUIValue('D', isDifferential, changed);
TryConfigureSensorName(gb, changed);
+ return FinishConfiguring(changed, reply);
+}
+#if SUPPORT_REMOTE_COMMANDS
+
+GCodeResult CurrentLoopTemperatureSensor::Configure(const CanMessageGenericParser& parser, const StringRef& reply) noexcept
+{
+ bool seen = false;
+ if (!ConfigurePort(parser, reply, seen))
+ {
+ return GCodeResult::error;
+ }
+
+ return FinishConfiguring(seen, reply);
+}
+
+#endif
+
+GCodeResult CurrentLoopTemperatureSensor::FinishConfiguring(bool changed, const StringRef& reply) noexcept
+{
if (changed)
{
CalcDerivedParameters();
@@ -135,4 +161,6 @@ TemperatureError CurrentLoopTemperatureSensor::TryGetLinearAdcTemperature(float&
return rslt;
}
+#endif // SUPPORT_SPI_SENSORS
+
// End
diff --git a/src/Heating/Sensors/CurrentLoopTemperatureSensor.h b/src/Heating/Sensors/CurrentLoopTemperatureSensor.h
index 0fd0133c..6b080f92 100644
--- a/src/Heating/Sensors/CurrentLoopTemperatureSensor.h
+++ b/src/Heating/Sensors/CurrentLoopTemperatureSensor.h
@@ -10,18 +10,26 @@
#include "SpiTemperatureSensor.h"
+#if SUPPORT_SPI_SENSORS
+
class CurrentLoopTemperatureSensor : public SpiTemperatureSensor
{
public:
CurrentLoopTemperatureSensor(unsigned int sensorNum) noexcept;
GCodeResult Configure(GCodeBuffer& gb, const StringRef& reply, bool& changed) override THROWS(GCodeException);
- const char *GetShortSensorType() const noexcept override { return TypeName; }
+
+#if SUPPORT_REMOTE_COMMANDS
+ GCodeResult Configure(const CanMessageGenericParser& parser, const StringRef& reply) noexcept override; // configure the sensor from M308 parameters
+#endif
+
void Poll() noexcept override;
+ const char *GetShortSensorType() const noexcept override { return TypeName; }
static constexpr const char *TypeName = "currentloop";
private:
TemperatureError TryGetLinearAdcTemperature(float& t) noexcept;
+ GCodeResult FinishConfiguring(bool changed, const StringRef& reply) noexcept;
void CalcDerivedParameters() noexcept;
// Configurable parameters
@@ -36,4 +44,6 @@ private:
static constexpr uint32_t DefaultChipChannel = 0;
};
+#endif // SUPPORT_SPI_SENSORS
+
#endif /* SRC_HEATING_LINEARADCTEMPERATURESENSOR_H_ */
diff --git a/src/Heating/Sensors/RtdSensor31865.cpp b/src/Heating/Sensors/RtdSensor31865.cpp
index 8815475c..6f8a4034 100644
--- a/src/Heating/Sensors/RtdSensor31865.cpp
+++ b/src/Heating/Sensors/RtdSensor31865.cpp
@@ -6,6 +6,9 @@
*/
#include "RtdSensor31865.h"
+
+#if SUPPORT_SPI_SENSORS
+
#include <Platform/RepRap.h>
#include <Platform/Platform.h>
#include <GCodes/GCodeBuffer/GCodeBuffer.h>
@@ -238,4 +241,6 @@ void RtdSensor31865::Poll() noexcept
}
}
+#endif // SUPPORT_SPI_SENSORS
+
// End
diff --git a/src/Heating/Sensors/RtdSensor31865.h b/src/Heating/Sensors/RtdSensor31865.h
index 18c242cd..ea2cc11e 100644
--- a/src/Heating/Sensors/RtdSensor31865.h
+++ b/src/Heating/Sensors/RtdSensor31865.h
@@ -10,6 +10,8 @@
#include "SpiTemperatureSensor.h"
+#if SUPPORT_SPI_SENSORS
+
class RtdSensor31865 : public SpiTemperatureSensor
{
public:
@@ -34,4 +36,6 @@ private:
uint8_t cr0;
};
+#endif //SUPPORT_SPI_SENSORS
+
#endif /* SRC_HEATING_RTDSENSOR31865_H_ */
diff --git a/src/Heating/Sensors/SpiTemperatureSensor.cpp b/src/Heating/Sensors/SpiTemperatureSensor.cpp
index fed34a72..f511b580 100644
--- a/src/Heating/Sensors/SpiTemperatureSensor.cpp
+++ b/src/Heating/Sensors/SpiTemperatureSensor.cpp
@@ -6,6 +6,9 @@
*/
#include "SpiTemperatureSensor.h"
+
+#if SUPPORT_SPI_SENSORS
+
#include <Platform/Tasks.h>
#include <Hardware/SharedSpi/SharedSpiDevice.h>
@@ -73,4 +76,6 @@ TemperatureError SpiTemperatureSensor::DoSpiTransaction(const uint8_t dataOut[],
return TemperatureError::success;
}
+#endif // SUPPORT_SPI_SENSORS
+
// End
diff --git a/src/Heating/Sensors/SpiTemperatureSensor.h b/src/Heating/Sensors/SpiTemperatureSensor.h
index ca78568c..52909d71 100644
--- a/src/Heating/Sensors/SpiTemperatureSensor.h
+++ b/src/Heating/Sensors/SpiTemperatureSensor.h
@@ -9,6 +9,9 @@
#define SRC_HEATING_SPITEMPERATURESENSOR_H_
#include "SensorWithPort.h"
+
+#if SUPPORT_SPI_SENSORS
+
#include <Hardware/SharedSpi/SharedSpiClient.h>
class SpiTemperatureSensor : public SensorWithPort
@@ -32,4 +35,6 @@ protected:
TemperatureError lastResult;
};
+#endif // SUPPORT_SPI_SENSORS
+
#endif /* SRC_HEATING_SPITEMPERATURESENSOR_H_ */
diff --git a/src/Heating/Sensors/TemperatureSensor.cpp b/src/Heating/Sensors/TemperatureSensor.cpp
index 070b2504..c326b6d1 100644
--- a/src/Heating/Sensors/TemperatureSensor.cpp
+++ b/src/Heating/Sensors/TemperatureSensor.cpp
@@ -203,6 +203,7 @@ TemperatureSensor *TemperatureSensor::Create(unsigned int sensorNum, const char
{
ts = new LinearAnalogSensor(sensorNum);
}
+#if SUPPORT_SPI_SENSORS
else if (ReducedStringEquals(typeName, ThermocoupleSensor31855::TypeName))
{
ts = new ThermocoupleSensor31855(sensorNum);
@@ -219,6 +220,7 @@ TemperatureSensor *TemperatureSensor::Create(unsigned int sensorNum, const char
{
ts = new CurrentLoopTemperatureSensor(sensorNum);
}
+#endif
#if SUPPORT_DHT_SENSOR
else if (ReducedStringEquals(typeName, DhtTemperatureSensor::TypeNameDht21))
{
diff --git a/src/Heating/Sensors/ThermocoupleSensor31855.cpp b/src/Heating/Sensors/ThermocoupleSensor31855.cpp
index 92081791..38da9524 100644
--- a/src/Heating/Sensors/ThermocoupleSensor31855.cpp
+++ b/src/Heating/Sensors/ThermocoupleSensor31855.cpp
@@ -46,6 +46,9 @@
// used by anything else as the Arduino Due leaves pin 78 unconnected.
#include "ThermocoupleSensor31855.h"
+
+#if SUPPORT_SPI_SENSORS
+
#include <Platform/RepRap.h>
#include <Platform/Platform.h>
#include <GCodes/GCodeBuffer/GCodeBuffer.h>
@@ -176,4 +179,6 @@ void ThermocoupleSensor31855::Poll() noexcept
}
}
+#endif // SUPPORT_SPI_SENSORS
+
// End
diff --git a/src/Heating/Sensors/ThermocoupleSensor31855.h b/src/Heating/Sensors/ThermocoupleSensor31855.h
index b5d62444..2a452e7c 100644
--- a/src/Heating/Sensors/ThermocoupleSensor31855.h
+++ b/src/Heating/Sensors/ThermocoupleSensor31855.h
@@ -10,6 +10,8 @@
#include "SpiTemperatureSensor.h"
+#if SUPPORT_SPI_SENSORS
+
class ThermocoupleSensor31855 : public SpiTemperatureSensor
{
public:
@@ -29,4 +31,6 @@ private:
GCodeResult FinishConfiguring(bool changed, const StringRef& reply) noexcept;
};
+#endif // SUPPORT_SPI_SENSORS
+
#endif /* SRC_HEATING_THERMOCOUPLESENSOR31855_H_ */
diff --git a/src/Heating/Sensors/ThermocoupleSensor31856.cpp b/src/Heating/Sensors/ThermocoupleSensor31856.cpp
index 6fe3e346..c4e9441e 100644
--- a/src/Heating/Sensors/ThermocoupleSensor31856.cpp
+++ b/src/Heating/Sensors/ThermocoupleSensor31856.cpp
@@ -6,6 +6,9 @@
*/
#include "ThermocoupleSensor31856.h"
+
+#if SUPPORT_SPI_SENSORS
+
#include <Platform/RepRap.h>
#include <Platform/Platform.h>
#include <GCodes/GCodeBuffer/GCodeBuffer.h>
@@ -242,4 +245,6 @@ void ThermocoupleSensor31856::Poll() noexcept
}
}
+#endif // SUPPORT_SPI_SENSORS
+
// End
diff --git a/src/Heating/Sensors/ThermocoupleSensor31856.h b/src/Heating/Sensors/ThermocoupleSensor31856.h
index 5633309c..e33d4042 100644
--- a/src/Heating/Sensors/ThermocoupleSensor31856.h
+++ b/src/Heating/Sensors/ThermocoupleSensor31856.h
@@ -10,6 +10,8 @@
#include "SpiTemperatureSensor.h"
+#if SUPPORT_SPI_SENSORS
+
class ThermocoupleSensor31856 : public SpiTemperatureSensor
{
public:
@@ -33,4 +35,6 @@ private:
uint8_t thermocoupleType;
};
+#endif // SUPPORT_SPI_SENSORS
+
#endif /* SRC_HEATING_SENSORS_THERMOCOUPLESENSOR31856_H_ */
diff --git a/src/Movement/DDA.cpp b/src/Movement/DDA.cpp
index e98c7042..880f02f5 100644
--- a/src/Movement/DDA.cpp
+++ b/src/Movement/DDA.cpp
@@ -316,8 +316,10 @@ bool DDA::InitStandardMove(DDARing& ring, const RawMove &nextMove, bool doMotorM
{
return false; // throw away the move if it couldn't be transformed
}
+#if SUPPORT_LINEAR_DELTA
flags.isDeltaMovement = move.IsDeltaMode()
&& (endPoint[X_AXIS] != positionNow[X_AXIS] || endPoint[Y_AXIS] != positionNow[Y_AXIS] || endPoint[Z_AXIS] != positionNow[Z_AXIS]);
+#endif
}
bool linearAxesMoving = false;
@@ -1085,6 +1087,7 @@ float DDA::AdvanceBabyStepping(DDARing& ring, size_t axis, float amount) noexcep
// Even if there is no babystepping to do this move, we may need to adjust the end coordinates
cdda->endCoordinates[Z_AXIS] += babySteppingDone;
+#if SUPPORT_LINEAR_DELTA
if (cdda->flags.isDeltaMovement)
{
for (size_t motor = 0; motor < reprap.GetGCodes().GetTotalAxes(); ++motor)
@@ -1096,6 +1099,7 @@ float DDA::AdvanceBabyStepping(DDARing& ring, size_t axis, float amount) noexcep
}
}
else
+#endif
{
cdda->endPoint[Z_AXIS] += (int32_t)(babySteppingDone * reprap.GetPlatform().DriveStepsPerUnit(Z_AXIS));
}
@@ -1320,26 +1324,28 @@ void DDA::Prepare(SimulationMode simMode) noexcept
if (simMode < SimulationMode::normal)
{
+#if SUPPORT_LINEAR_DELTA
if (flags.isDeltaMovement)
{
// This code assumes that the previous move in the DDA ring is the previously-executed move, because it fetches the X and Y end coordinates from that move.
// Therefore the Move code must not store a new move in that entry until this one has been prepared! (It took me ages to track this down.)
// Ideally we would store the initial X and Y coordinates in the DDA, but we need to be economical with memory
-#if MS_USE_FPU
+# if MS_USE_FPU
// Nothing needed here, use directionVector[Z_AXIS] directly
-#else
+# else
afterPrepare.cKc = lrintf(directionVector[Z_AXIS] * MoveSegment::KdirectionVector);
-#endif
+# endif
params.a2plusb2 = fsquare(directionVector[X_AXIS]) + fsquare(directionVector[Y_AXIS]);
params.initialX = prev->GetEndCoordinate(X_AXIS, false);
params.initialY = prev->GetEndCoordinate(Y_AXIS, false);
-#if SUPPORT_CAN_EXPANSION
+ params.dparams = static_cast<const LinearDeltaKinematics*>(&(reprap.GetMove().GetKinematics()));
+# if SUPPORT_CAN_EXPANSION
params.finalX = GetEndCoordinate(X_AXIS, false);
params.finalY = GetEndCoordinate(Y_AXIS, false);
params.zMovement = GetEndCoordinate(Z_AXIS, false) - prev->GetEndCoordinate(Z_AXIS, false);
-#endif
- params.dparams = static_cast<const LinearDeltaKinematics*>(&(reprap.GetMove().GetKinematics()));
+# endif
}
+#endif
activeDMs = completedDMs = nullptr;
@@ -1405,6 +1411,7 @@ void DDA::Prepare(SimulationMode simMode) noexcept
}
}
}
+#if SUPPORT_LINEAR_DELTA
else if (flags.isDeltaMovement && reprap.GetMove().GetKinematics().GetMotionType(drive) == MotionType::segmentFreeDelta)
{
// On a delta we need to move all towers even if some of them have no net movement
@@ -1438,7 +1445,7 @@ void DDA::Prepare(SimulationMode simMode) noexcept
}
}
-#if SUPPORT_CAN_EXPANSION
+# if SUPPORT_CAN_EXPANSION
afterPrepare.drivesMoving.SetBit(drive);
const AxisDriversConfig& config = platform.GetAxisDriversConfig(drive);
for (size_t i = 0; i < config.numDrivers; ++i)
@@ -1449,9 +1456,10 @@ void DDA::Prepare(SimulationMode simMode) noexcept
CanMotion::AddMovement(params, driver, delta, false);
}
}
-#endif
+# endif
axisMotorsEnabled.SetBit(drive);
}
+#endif
else if (drive < reprap.GetGCodes().GetTotalAxes())
{
// It's a linear axis
diff --git a/src/Movement/DDA.h b/src/Movement/DDA.h
index 290c6d69..c4ce6b34 100644
--- a/src/Movement/DDA.h
+++ b/src/Movement/DDA.h
@@ -51,14 +51,16 @@ struct PrepParams
float initialSpeedFraction, finalSpeedFraction;
#endif
+#if SUPPORT_LINEAR_DELTA
// Parameters used only for delta moves
float initialX, initialY;
-#if SUPPORT_CAN_EXPANSION
+# if SUPPORT_CAN_EXPANSION
float finalX, finalY;
float zMovement;
-#endif
+# endif
const LinearDeltaKinematics *dparams;
float a2plusb2; // sum of the squares of the X and Y movement fractions
+#endif
// Set up the parameters from the DDA, excluding steadyClocks because that may be affected by input shaping
void SetFromDDA(const DDA& dda) noexcept;
@@ -272,8 +274,10 @@ private:
{
struct
{
- uint16_t endCoordinatesValid : 1, // True if endCoordinates can be relied on
+ uint16_t endCoordinatesValid : 1, // True if endCoordinates can be relied
+#if SUPPORT_LINEAR_DELTA
isDeltaMovement : 1, // True if this is a delta printer movement
+#endif
canPauseAfter : 1, // True if we can pause at the end of this move
isPrintingMove : 1, // True if this move includes XY movement and extrusion
usePressureAdvance : 1, // True if pressure advance should be applied to any forward extrusion
@@ -340,7 +344,7 @@ private:
static_assert(MaxAxesPlusExtruders <= DriversBitmap::MaxBits());
#endif
// These are used only in delta calculations
-#if !MS_USE_FPU
+#if SUPPORT_LINEAR_DELTA && !MS_USE_FPU
int32_t cKc; // The Z movement fraction multiplied by Kc and converted to integer
#endif
} afterPrepare;
diff --git a/src/Movement/DriveMovement.cpp b/src/Movement/DriveMovement.cpp
index 77351302..fce12e1f 100644
--- a/src/Movement/DriveMovement.cpp
+++ b/src/Movement/DriveMovement.cpp
@@ -172,6 +172,8 @@ bool DriveMovement::NewCartesianSegment() noexcept
}
}
+#if SUPPORT_LINEAR_DELTA
+
// This is called when currentSegment has just been changed to a new segment. Return true if there is a new segment to execute.
bool DriveMovement::NewDeltaSegment(const DDA& dda) noexcept
{
@@ -311,6 +313,8 @@ bool DriveMovement::NewDeltaSegment(const DDA& dda) noexcept
}
}
+#endif // SUPPORT_LINEAR_DELTA
+
// This is called when currentSegment has just been changed to a new segment. Return true if there is a new segment to execute.
bool DriveMovement::NewExtruderSegment() noexcept
{
@@ -437,6 +441,8 @@ bool DriveMovement::PrepareCartesianAxis(const DDA& dda, const PrepParams& param
return CalcNextStepTime(dda);
}
+#if SUPPORT_LINEAR_DELTA
+
// Prepare this DM for a Delta axis move, returning true if there are steps to do
bool DriveMovement::PrepareDeltaAxis(const DDA& dda, const PrepParams& params) noexcept
{
@@ -616,6 +622,8 @@ bool DriveMovement::PrepareDeltaAxis(const DDA& dda, const PrepParams& params) n
return CalcNextStepTime(dda);
}
+#endif // SUPPORT_LINEAR_DELTA
+
// Prepare this DM for an extruder move, returning true if there are steps to do
// If there are no steps to do, set nextStep = 0 so that DDARing::CurrentMoveCompleted doesn't add any steps to the movement accumulator
// We have already generated the extruder segments and we know that there are some
@@ -902,9 +910,12 @@ pre(nextStep <= totalSteps; stepsTillRecalc == 0)
if (stepsToLimit == 0)
{
currentSegment = currentSegment->GetNext();
- const bool more = (isDelta) ? NewDeltaSegment(dda)
- : (isExtruder) ? NewExtruderSegment()
- : NewCartesianSegment();
+ const bool more =
+#if SUPPORT_LINEAR_DELTA
+ (isDelta) ? NewDeltaSegment(dda) :
+#endif
+ (isExtruder) ? NewExtruderSegment()
+ : NewCartesianSegment();
if (!more)
{
state = DMState::stepError;
diff --git a/src/Movement/DriveMovement.h b/src/Movement/DriveMovement.h
index 0315e808..473091d3 100644
--- a/src/Movement/DriveMovement.h
+++ b/src/Movement/DriveMovement.h
@@ -50,7 +50,9 @@ public:
bool CalcNextStepTime(const DDA &dda) noexcept SPEED_CRITICAL;
bool PrepareCartesianAxis(const DDA& dda, const PrepParams& params) noexcept SPEED_CRITICAL;
+#if SUPPORT_LINEAR_DELTA
bool PrepareDeltaAxis(const DDA& dda, const PrepParams& params) noexcept SPEED_CRITICAL;
+#endif
bool PrepareExtruder(const DDA& dda, const PrepParams& params) noexcept SPEED_CRITICAL;
void DebugPrint() const noexcept;
@@ -70,7 +72,9 @@ private:
bool CalcNextStepTimeFull(const DDA &dda) noexcept SPEED_CRITICAL;
bool NewCartesianSegment() noexcept SPEED_CRITICAL;
bool NewExtruderSegment() noexcept SPEED_CRITICAL;
+#if SUPPORT_LINEAR_DELTA
bool NewDeltaSegment(const DDA& dda) noexcept SPEED_CRITICAL;
+#endif
static DriveMovement *freeList;
static unsigned int numCreated;
diff --git a/src/Movement/Kinematics/FiveBarScaraKinematics.cpp b/src/Movement/Kinematics/FiveBarScaraKinematics.cpp
index fe44440b..7615e261 100644
--- a/src/Movement/Kinematics/FiveBarScaraKinematics.cpp
+++ b/src/Movement/Kinematics/FiveBarScaraKinematics.cpp
@@ -8,6 +8,9 @@
*/
#include "FiveBarScaraKinematics.h"
+
+#if SUPPORT_FIVEBARSCARA
+
#include <Platform/RepRap.h>
#include <Platform/Platform.h>
#include <Storage/MassStorage.h>
@@ -948,4 +951,6 @@ void FiveBarScaraKinematics::Recalc() noexcept
cachedInvalid = true;
}
+#endif // SUPPORT_FIVEBARSCARA
+
// End
diff --git a/src/Movement/Kinematics/FiveBarScaraKinematics.h b/src/Movement/Kinematics/FiveBarScaraKinematics.h
index 7c20a9ca..beaa5905 100644
--- a/src/Movement/Kinematics/FiveBarScaraKinematics.h
+++ b/src/Movement/Kinematics/FiveBarScaraKinematics.h
@@ -12,6 +12,8 @@
#include "ZLeadscrewKinematics.h"
+#if SUPPORT_FIVEBARSCARA
+
// Standard setup for 5 Bar SCARA (parallel SCARA) machines assumed by this firmware
enum class Arm : uint8_t
{
@@ -103,4 +105,6 @@ private:
mutable bool cachedInvalid;
};
+#endif // SUPPORT_FIVEBARSCARA
+
#endif /* SRC_MOVEMENT_KINEMATICS_FIVEBARSCARAKINEMATICS_H_ */
diff --git a/src/Movement/Kinematics/HangprinterKinematics.cpp b/src/Movement/Kinematics/HangprinterKinematics.cpp
index a99e71ae..71566e83 100644
--- a/src/Movement/Kinematics/HangprinterKinematics.cpp
+++ b/src/Movement/Kinematics/HangprinterKinematics.cpp
@@ -6,6 +6,9 @@
*/
#include "HangprinterKinematics.h"
+
+#if SUPPORT_HANGPRINTER
+
#include <Platform/RepRap.h>
#include <Platform/Platform.h>
#include <GCodes/GCodeBuffer/GCodeBuffer.h>
@@ -521,7 +524,7 @@ void HangprinterKinematics::ForwardTransform(float const a, float const b, float
{
// Force the anchor location norms Ax=0, Dx=0, Dy=0
// through a series of rotations.
- float const x_angle = atan(anchors[D_AXIS][Y_AXIS]/anchors[D_AXIS][Z_AXIS]);
+ float const x_angle = atanf(anchors[D_AXIS][Y_AXIS]/anchors[D_AXIS][Z_AXIS]);
float const rxt[3][3] = {{1, 0, 0}, {0, cosf(x_angle), sinf(x_angle)}, {0, -sinf(x_angle), cosf(x_angle)}};
float anchors_tmp0[4][3] = { 0 };
for (size_t row{0}; row < 4; ++row) {
@@ -529,7 +532,7 @@ void HangprinterKinematics::ForwardTransform(float const a, float const b, float
anchors_tmp0[row][col] = rxt[0][col]*anchors[row][0] + rxt[1][col]*anchors[row][1] + rxt[2][col]*anchors[row][2];
}
}
- float const y_angle = atan(-anchors_tmp0[D_AXIS][X_AXIS]/anchors_tmp0[D_AXIS][Z_AXIS]);
+ float const y_angle = atanf(-anchors_tmp0[D_AXIS][X_AXIS]/anchors_tmp0[D_AXIS][Z_AXIS]);
float const ryt[3][3] = {{cosf(y_angle), 0, -sinf(y_angle)}, {0, 1, 0}, {sinf(y_angle), 0, cosf(y_angle)}};
float anchors_tmp1[4][3] = { 0 };
for (size_t row{0}; row < 4; ++row) {
@@ -537,7 +540,7 @@ void HangprinterKinematics::ForwardTransform(float const a, float const b, float
anchors_tmp1[row][col] = ryt[0][col]*anchors_tmp0[row][0] + ryt[1][col]*anchors_tmp0[row][1] + ryt[2][col]*anchors_tmp0[row][2];
}
}
- float const z_angle = atan(anchors_tmp1[A_AXIS][X_AXIS]/anchors_tmp1[A_AXIS][Y_AXIS]);
+ float const z_angle = atanf(anchors_tmp1[A_AXIS][X_AXIS]/anchors_tmp1[A_AXIS][Y_AXIS]);
float const rzt[3][3] = {{cosf(z_angle), sinf(z_angle), 0}, {-sinf(z_angle), cosf(z_angle), 0}, {0, 0, 1}};
for (size_t row{0}; row < 4; ++row) {
for (size_t col{0}; col < 3; ++col) {
@@ -778,4 +781,6 @@ GCodeResult HangprinterKinematics::SetODrive3TorqueMode(DriverId const driver, f
}
#endif // DUAL_CAN
+#endif // SUPPORT_HANGPRINTER
+
// End
diff --git a/src/Movement/Kinematics/HangprinterKinematics.h b/src/Movement/Kinematics/HangprinterKinematics.h
index 6a64977d..8584a389 100644
--- a/src/Movement/Kinematics/HangprinterKinematics.h
+++ b/src/Movement/Kinematics/HangprinterKinematics.h
@@ -10,6 +10,8 @@
#include "RoundBedKinematics.h"
+#if SUPPORT_HANGPRINTER
+
class HangprinterKinematics : public RoundBedKinematics
{
public:
@@ -137,4 +139,6 @@ class CANSimple {
static const int32_t INPUT_MODE_TUNING = 8;
};
+#endif // SUPPORT_HANGPRINTER
+
#endif /* SRC_MOVEMENT_KINEMATICS_HANGPRINTERKINEMATICS_H_ */
diff --git a/src/Movement/Kinematics/Kinematics.cpp b/src/Movement/Kinematics/Kinematics.cpp
index e2ebdc71..6ccc5f9d 100644
--- a/src/Movement/Kinematics/Kinematics.cpp
+++ b/src/Movement/Kinematics/Kinematics.cpp
@@ -238,18 +238,35 @@ void Kinematics::LimitSpeedAndAcceleration(DDA& dda, const float *normalisedDire
case KinematicsType::markForged:
return new CoreKinematics(k);
+#if SUPPORT_LINEAR_DELTA
case KinematicsType::linearDelta:
return new LinearDeltaKinematics();
+#endif
+
+#if SUPPORT_SCARA
case KinematicsType::scara:
return new ScaraKinematics();
+#endif
+
+#if SUPPORT_HANGPRINTER
case KinematicsType::hangprinter:
return new HangprinterKinematics();
+#endif
+
+#if SUPPORT_POLAR
case KinematicsType::polar:
return new PolarKinematics();
+#endif
+
+#if SUPPORT_ROTARY_DELTA
case KinematicsType::rotaryDelta:
return new RotaryDeltaKinematics();
+#endif
+
+#if SUPPORT_FIVEBARSCARA
case KinematicsType::fiveBarScara:
return new FiveBarScaraKinematics();
+#endif
}
}
diff --git a/src/Movement/Kinematics/LinearDeltaKinematics.cpp b/src/Movement/Kinematics/LinearDeltaKinematics.cpp
index 13f951a5..e0d2ff10 100644
--- a/src/Movement/Kinematics/LinearDeltaKinematics.cpp
+++ b/src/Movement/Kinematics/LinearDeltaKinematics.cpp
@@ -7,6 +7,8 @@
#include "LinearDeltaKinematics.h"
+#if SUPPORT_LINEAR_DELTA
+
#include <Movement/Move.h>
#include <Platform/RepRap.h>
#include <Storage/FileStore.h>
@@ -1046,4 +1048,6 @@ AxesBitmap LinearDeltaKinematics::GetLinearAxes() const noexcept
return AxesBitmap::MakeFromBits(Z_AXIS);
}
+#endif // SUPPORT_LINEAR_DELTA
+
// End
diff --git a/src/Movement/Kinematics/LinearDeltaKinematics.h b/src/Movement/Kinematics/LinearDeltaKinematics.h
index 0132c33e..8bd55d5d 100644
--- a/src/Movement/Kinematics/LinearDeltaKinematics.h
+++ b/src/Movement/Kinematics/LinearDeltaKinematics.h
@@ -9,6 +9,9 @@
#define LINEARDELTAKINEMATICS_H_
#include "RepRapFirmware.h"
+
+#if SUPPORT_LINEAR_DELTA
+
#include "RoundBedKinematics.h"
// Class to hold the parameter for a delta machine.
@@ -106,4 +109,6 @@ private:
bool doneAutoCalibration; // True if we have done auto calibration
};
+#endif // SUPPORT_LINEAR_DELTA
+
#endif /* LINEARDELTAKINEMATICS_H_ */
diff --git a/src/Movement/Kinematics/PolarKinematics.cpp b/src/Movement/Kinematics/PolarKinematics.cpp
index 25a26735..1e00c145 100644
--- a/src/Movement/Kinematics/PolarKinematics.cpp
+++ b/src/Movement/Kinematics/PolarKinematics.cpp
@@ -7,6 +7,8 @@
#include "PolarKinematics.h"
+#if SUPPORT_POLAR
+
#include <Platform/RepRap.h>
#include <Platform/Platform.h>
#include <Storage/MassStorage.h>
@@ -340,4 +342,6 @@ void PolarKinematics::Recalc()
maxRadiusSquared = fsquare(maxRadius);
}
+#endif // SUPPORT_POLAR
+
// End
diff --git a/src/Movement/Kinematics/PolarKinematics.h b/src/Movement/Kinematics/PolarKinematics.h
index 60483b38..0cb0951f 100644
--- a/src/Movement/Kinematics/PolarKinematics.h
+++ b/src/Movement/Kinematics/PolarKinematics.h
@@ -10,6 +10,8 @@
#include "Kinematics.h"
+#if SUPPORT_POLAR
+
class PolarKinematics : public Kinematics
{
public:
@@ -51,4 +53,6 @@ private:
float minRadiusSquared, maxRadiusSquared;
};
+#endif // SUPPORT_POLAR
+
#endif /* SRC_MOVEMENT_KINEMATICS_POLARKINEMATICS_H_ */
diff --git a/src/Movement/Kinematics/RotaryDeltaKinematics.cpp b/src/Movement/Kinematics/RotaryDeltaKinematics.cpp
index 9ef081a2..eb2b8fc3 100644
--- a/src/Movement/Kinematics/RotaryDeltaKinematics.cpp
+++ b/src/Movement/Kinematics/RotaryDeltaKinematics.cpp
@@ -7,6 +7,8 @@
#include "RotaryDeltaKinematics.h"
+#if SUPPORT_ROTARY_DELTA
+
#include <Movement/Move.h>
#include <Platform/RepRap.h>
#include <Storage/FileStore.h>
@@ -813,4 +815,6 @@ void RotaryDeltaKinematics::ForwardTransform(float Ha, float Hb, float Hc, float
}
}
+#endif // SUPPORT_ROTARY_DELTA
+
// End
diff --git a/src/Movement/Kinematics/RotaryDeltaKinematics.h b/src/Movement/Kinematics/RotaryDeltaKinematics.h
index b0361fdb..9c916010 100644
--- a/src/Movement/Kinematics/RotaryDeltaKinematics.h
+++ b/src/Movement/Kinematics/RotaryDeltaKinematics.h
@@ -10,6 +10,8 @@
#include "RoundBedKinematics.h"
+#if SUPPORT_ROTARY_DELTA
+
class RotaryDeltaKinematics : public RoundBedKinematics
{
public:
@@ -92,4 +94,6 @@ private:
bool doneAutoCalibration; // True if we have done auto calibration
};
+#endif // SUPPORT_ROTARY_DELTA
+
#endif /* SRC_MOVEMENT_KINEMATICS_ROTARYDELTAKINEMATICS_H_ */
diff --git a/src/Movement/Kinematics/ScaraKinematics.cpp b/src/Movement/Kinematics/ScaraKinematics.cpp
index c6c95e30..2ff4597e 100644
--- a/src/Movement/Kinematics/ScaraKinematics.cpp
+++ b/src/Movement/Kinematics/ScaraKinematics.cpp
@@ -6,6 +6,9 @@
*/
#include "ScaraKinematics.h"
+
+#if SUPPORT_SCARA
+
#include <Platform/RepRap.h>
#include <Platform/Platform.h>
#include <Storage/MassStorage.h>
@@ -494,4 +497,6 @@ void ScaraKinematics::Recalc() noexcept
cachedX = cachedY = std::numeric_limits<float>::quiet_NaN(); // make sure that the cached values won't match any coordinates
}
+#endif // SUPPORT_SCARA
+
// End
diff --git a/src/Movement/Kinematics/ScaraKinematics.h b/src/Movement/Kinematics/ScaraKinematics.h
index 2a6920bf..27d69999 100644
--- a/src/Movement/Kinematics/ScaraKinematics.h
+++ b/src/Movement/Kinematics/ScaraKinematics.h
@@ -10,6 +10,8 @@
#include "ZLeadscrewKinematics.h"
+#if SUPPORT_SCARA
+
// Standard setup for SCARA machines assumed by this firmware
// The X motor output drives the proximal arm joint, unless remapped using M584
// The Y motor output drives the distal arm joint, unless remapped using M584
@@ -83,4 +85,6 @@ private:
mutable bool currentArmMode, cachedArmMode;
};
+#endif // SUPPORT_SCARA
+
#endif /* SRC_MOVEMENT_KINEMATICS_SCARAKINEMATICS_H_ */
diff --git a/src/Movement/Move.h b/src/Movement/Move.h
index 5d274600..057c79b4 100644
--- a/src/Movement/Move.h
+++ b/src/Movement/Move.h
@@ -121,7 +121,9 @@ public:
bool IsAccessibleProbePoint(float axesCoords[MaxAxes], AxesBitmap axes) const noexcept;
// Temporary kinematics functions
+#if SUPPORT_LINEAR_DELTA
bool IsDeltaMode() const noexcept { return kinematics->GetKinematicsType() == KinematicsType::linearDelta; }
+#endif
// End temporary functions
bool IsRawMotorMove(uint8_t moveType) const noexcept; // Return true if this is a raw motor move
diff --git a/src/Platform/Platform.cpp b/src/Platform/Platform.cpp
index c16cb8f8..bad21c1b 100644
--- a/src/Platform/Platform.cpp
+++ b/src/Platform/Platform.cpp
@@ -407,7 +407,7 @@ Platform::Platform() noexcept :
board(DEFAULT_BOARD_TYPE), active(false), errorCodeBits(0),
nextDriveToPoll(0),
lastFanCheckTime(0),
-#if HAS_AUX_DEVICES
+#if SUPPORT_PANELDUE_FLASH
panelDueUpdater(nullptr),
#endif
#if HAS_MASS_STORAGE || HAS_SBC_INTERFACE || HAS_EMBEDDED_FILES
@@ -429,10 +429,6 @@ Platform::Platform() noexcept :
// Initialise the Platform. Note: this is the first module to be initialised, so don't call other modules from here!
void Platform::Init() noexcept
{
-#if defined(DUET3) || defined(DUET3MINI)
- pinMode(EthernetPhyResetPin, OUTPUT_LOW); // hold the Ethernet Phy chip in reset, hopefully this will prevent it being too noisy if Ethernet is not enabled
-#endif
-
// Make sure the on-board drivers are disabled
#if defined(DUET_NG) || defined(PCCB_10)
pinMode(GlobalTmc2660EnablePin, OUTPUT_HIGH);
@@ -3210,7 +3206,7 @@ void Platform::SetAuxRaw(size_t auxNumber, bool raw) noexcept
#endif
}
-#if HAS_AUX_DEVICES
+#if SUPPORT_PANELDUE_FLASH
void Platform::InitPanelDueUpdater() noexcept
{
if (panelDueUpdater == nullptr)
@@ -3792,6 +3788,8 @@ void Platform::SetBoardType(BoardType bt) noexcept
board = (digitalRead(DIRECTION_PINS[0])) ? BoardType::Duet3_6HC_v101 : BoardType::Duet3_6HC_v06_100;
#elif defined(DUET3_MB6XD)
board = BoardType::Duet3_6XD;
+#elif defined(DUET3MINI4)
+ board = BoardType::Duet3Mini4;
#elif defined(SAME70XPLD)
board = BoardType::SAME70XPLD_0;
#elif defined(DUET_NG)
@@ -3861,7 +3859,7 @@ const char *_ecv_array Platform::GetElectronicsString() const noexcept
{
switch (board)
{
-#if defined(DUET3MINI)
+#if defined(DUET3MINI_V04)
case BoardType::Duet3Mini_Unknown: return "Duet 3 " BOARD_SHORT_NAME " unknown variant";
case BoardType::Duet3Mini_WiFi: return "Duet 3 " BOARD_SHORT_NAME " WiFi";
case BoardType::Duet3Mini_Ethernet: return "Duet 3 " BOARD_SHORT_NAME " Ethernet";
@@ -3870,6 +3868,8 @@ const char *_ecv_array Platform::GetElectronicsString() const noexcept
case BoardType::Duet3_6HC_v101: return "Duet 3 " BOARD_SHORT_NAME " v1.01 or later";
#elif defined(DUET3_MB6XD)
case BoardType::Duet3_6XD: return "Duet 3 " BOARD_SHORT_NAME; // we have only one version at present
+#elif defined(DUET3MINI4)
+ case BoardType::Duet3Mini4: return "Duet 3 " BOARD_SHORT_NAME;
#elif defined(SAME70XPLD)
case BoardType::SAME70XPLD_0: return "SAME70-XPLD";
#elif defined(DUET_NG)
@@ -3898,7 +3898,7 @@ const char *_ecv_array Platform::GetBoardString() const noexcept
{
switch (board)
{
-#if defined(DUET3MINI)
+#if defined(DUET3MINI_V04)
case BoardType::Duet3Mini_Unknown: return "duet5lcunknown";
case BoardType::Duet3Mini_WiFi: return "duet5lcwifi";
case BoardType::Duet3Mini_Ethernet: return "duet5lcethernet";
@@ -3907,6 +3907,8 @@ const char *_ecv_array Platform::GetBoardString() const noexcept
case BoardType::Duet3_6HC_v101: return "duet3mb6hc101";
#elif defined(DUET3_MB6XD)
case BoardType::Duet3_6XD: return "duet3mb6xd"; // we have only one version at present
+#elif defined(DUET3MINI4)
+ case BoardType::Duet3Mini4: return "duet3mini4";
#elif defined(SAME70XPLD)
case BoardType::SAME70XPLD_0: return "same70xpld";
#elif defined(DUET_NG)
@@ -3953,7 +3955,7 @@ const char *_ecv_array Platform::GetBoardShortName() const noexcept
#endif
-#ifdef DUET3MINI
+#ifdef DUET3MINI_V04
// Return true if this is a WiFi board, false if it has Ethernet
bool Platform::IsDuetWiFi() const noexcept
diff --git a/src/Platform/Platform.h b/src/Platform/Platform.h
index df74dad2..4035aeb5 100644
--- a/src/Platform/Platform.h
+++ b/src/Platform/Platform.h
@@ -119,7 +119,7 @@ constexpr uint32_t maxPidSpinDelay = 5000; // Maximum elapsed time in millisec
enum class BoardType : uint8_t
{
Auto = 0,
-#if defined(DUET3MINI) // we use the same values for both v0.2 and v0.4
+#if defined(DUET3MINI_V04) // we use the same values for both v0.2 and v0.4
Duet3Mini_Unknown,
Duet3Mini_WiFi,
Duet3Mini_Ethernet,
@@ -128,6 +128,8 @@ enum class BoardType : uint8_t
Duet3_6HC_v101 = 2,
#elif defined(DUET3_MB6XD)
Duet3_6XD = 1,
+#elif defined(DUET3MINI4)
+ Duet3Mini4,
#elif defined(SAME70XPLD)
SAME70XPLD_0 = 1
#elif defined(DUET_NG)
@@ -386,7 +388,7 @@ public:
void EnableAux(size_t auxNumber) noexcept;
bool IsAuxRaw(size_t auxNumber) const noexcept;
void SetAuxRaw(size_t auxNumber, bool raw) noexcept;
-#if HAS_AUX_DEVICES
+#if SUPPORT_PANELDUE_FLASH
PanelDueUpdater* GetPanelDueUpdater() noexcept { return panelDueUpdater; }
void InitPanelDueUpdater() noexcept;
#endif
@@ -859,6 +861,8 @@ private:
#if HAS_AUX_DEVICES
AuxDevice auxDevices[NumSerialChannels - 1];
+#endif
+#if SUPPORT_PANELDUE_FLASH
PanelDueUpdater* panelDueUpdater;
#endif
diff --git a/src/Version.h b/src/Version.h
index c0848d1f..323d79ca 100644
--- a/src/Version.h
+++ b/src/Version.h
@@ -10,7 +10,7 @@
#ifndef VERSION
// Note: the complete VERSION string must be in standard version number format and must not contain spaces! This is so that DWC can parse it.
-# define MAIN_VERSION "3.4.0beta7+8"
+# define MAIN_VERSION "3.4.0rc1"
# ifdef USE_CAN0
# define VERSION_SUFFIX "(CAN0)"
# else