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:
authorDavid Crocker <dcrocker@eschertech.com>2018-10-17 00:08:50 +0300
committerDavid Crocker <dcrocker@eschertech.com>2018-10-17 00:08:50 +0300
commit1347ea638627e7969ea1fa6f059d497c8692925a (patch)
tree77bc84037f64dd6efe63ce045e61b12e3eb95d32
parentbc93fe18d311e25e68b553ceeea9dd1b35262bf6 (diff)
Nearly version 2.02RC3
New G/M code features since 2.02RC2: G10 L2 and G10 L20 can now be used with no P parameter, meaning use the current coordinate system G60 now saves the current tool as well as the current user coordinates M116 now accepts an optional S parameter to specify the acceptable temperature difference M205 is supported to set the jerk limits (in mm/sec) as an alternative to M566 M208 now accepts Xaa:bb Ycc:dd etc. as an alternative to separate M208 S0 and M208 s1 commands M305 temperature sensor type 300-307 now supports a C parameter to select the input channel and a D parameter to select differential mode M408 now accepts a P parameter. P0 (default) gives the previous behaviour. P1 S"filter" now returns those parts of the object model that match "filter". M557 now supports a P parameter to set the number of X and Y points, as an alternative to using the S parameter to set the spacing M558: zero or negative Z probe tolerance (S parameter) with A parameter > 1 now means always average all readings M558 now accepts a C parameter to select the endstop number when the mode is 4. M558 P6 is translated to M558 P4 C4, and M558 P7 is translated to M558 P4 C2. M600 is now supported T R# (where # is a restore point number) is now supported - Other changed behaviour since 2.02RC2: When storage module debug is enabled, failing to open a file is now a warning not an error because it is a normal accurrence when optional files are not present (e.g. tool change files, start.g, stop.g) Increased number of restore points from 3 to 6 When the WiFi module is in client mode it tries to auto-reconnect continuously if the connection is lost Implemented the object model framework and a few variables Z leadscrew or manual be levelling adjustment results are now logged even if the process failed, if logging is enabled Mesh probing results are now logged, if logging is enabled Error and warning messages generated by incorrect GCode commands are now logged, if logging is enabled - Bug fixes since 2.02RC2: The motor phase open circuit message is clearer, is now a warning instead of an error, and spurious instances of it should be reduced M918 with no parameters now reports current settings (Duet 2 Maestro) Further limited the amount of CPU time used to refresh the 12864 display Fixed incorrect check for G2/G3 missing parameter Fix CoreXYUV stall detection Absolute babystepping was be restricted to 1mm change After using G10 L2 or G10 L20 to change workplace coordinate offsets, the user positions of axes other than X and Y were not updated M915 now recognises the E parameter M915 output was truncated if no drives were specified On the Duet 2 Maestro, if a BLTouch Z probe was used then the pin didn't always stay retracted after the probe was triggered On the Duet 2 Maestro, if the SD card menu on the 12864 display was used then the network kept disconnecting If G30 S-1 was sent with the Z probe type set to zero then reported trigger height was an undefined value Fixed potential buffer overflow issues in 12864 menu code - Other changes: Introduced class IPAddres and refactored most usage oif IP addresses
-rw-r--r--.cproject32
-rw-r--r--src/BugList.txt88
-rw-r--r--src/Configuration.h6
-rw-r--r--src/Display/Display.cpp20
-rw-r--r--src/Display/Menu.cpp71
-rw-r--r--src/Display/Menu.h5
-rw-r--r--src/Display/MenuItem.cpp479
-rw-r--r--src/Display/MenuItem.h55
-rw-r--r--src/Display/RotaryEncoder.h1
-rw-r--r--src/Display/ST7920/lcd7920.cpp353
-rw-r--r--src/Display/ST7920/lcd7920.h40
-rw-r--r--src/Duet3/Pins_Duet3.h44
-rw-r--r--src/DuetM/Pins_DuetM.h13
-rw-r--r--src/DuetNG/Pins_DuetNG.h15
-rw-r--r--src/GCodes/GCodeBuffer.cpp195
-rw-r--r--src/GCodes/GCodeBuffer.h15
-rw-r--r--src/GCodes/GCodeMachineState.h3
-rw-r--r--src/GCodes/GCodeResult.h4
-rw-r--r--src/GCodes/GCodes.cpp184
-rw-r--r--src/GCodes/GCodes.h23
-rw-r--r--src/GCodes/GCodes2.cpp235
-rw-r--r--src/GCodes/GCodes3.cpp176
-rw-r--r--src/Heating/Heat.cpp8
-rw-r--r--src/Heating/Heat.h5
-rw-r--r--src/Heating/Sensors/CurrentLoopTemperatureSensor.cpp10
-rw-r--r--src/Heating/Sensors/CurrentLoopTemperatureSensor.h5
-rw-r--r--src/Movement/BedProbing/Grid.cpp18
-rw-r--r--src/Movement/BedProbing/Grid.h6
-rw-r--r--src/Movement/BedProbing/RandomProbePointSet.cpp18
-rw-r--r--src/Movement/BedProbing/RandomProbePointSet.h8
-rw-r--r--src/Movement/DDA.cpp37
-rw-r--r--src/Movement/DriveMovement.h4
-rw-r--r--src/Movement/Kinematics/HangprinterKinematics.cpp5
-rw-r--r--src/Movement/Kinematics/HangprinterKinematics.h2
-rw-r--r--src/Movement/Kinematics/Kinematics.cpp23
-rw-r--r--src/Movement/Kinematics/Kinematics.h7
-rw-r--r--src/Movement/Kinematics/LinearDeltaKinematics.cpp17
-rw-r--r--src/Movement/Kinematics/LinearDeltaKinematics.h2
-rw-r--r--src/Movement/Kinematics/PolarKinematics.cpp22
-rw-r--r--src/Movement/Kinematics/PolarKinematics.h2
-rw-r--r--src/Movement/Kinematics/RotaryDeltaKinematics.cpp17
-rw-r--r--src/Movement/Kinematics/RotaryDeltaKinematics.h2
-rw-r--r--src/Movement/Kinematics/ScaraKinematics.cpp36
-rw-r--r--src/Movement/Kinematics/ScaraKinematics.h2
-rw-r--r--src/Movement/Kinematics/ZLeadscrewKinematics.cpp11
-rw-r--r--src/Movement/Move.cpp23
-rw-r--r--src/Movement/Move.h8
-rw-r--r--src/Movement/StepTimer.cpp27
-rw-r--r--src/Movement/StepperDrivers/TMC22xx.cpp9
-rw-r--r--src/Movement/StepperDrivers/TMC2660.cpp4
-rw-r--r--src/Networking/ESP8266WiFi/WiFiInterface.cpp83
-rw-r--r--src/Networking/ESP8266WiFi/WiFiInterface.h13
-rw-r--r--src/Networking/ESP8266WiFi/WiFiSocket.cpp2
-rw-r--r--src/Networking/FtpResponder.cpp4
-rw-r--r--src/Networking/HttpResponder.cpp8
-rw-r--r--src/Networking/HttpResponder.h2
-rw-r--r--src/Networking/LwipEthernet/LwipEthernetInterface.cpp52
-rw-r--r--src/Networking/LwipEthernet/LwipEthernetInterface.h7
-rw-r--r--src/Networking/LwipEthernet/LwipSocket.cpp2
-rw-r--r--src/Networking/Network.cpp33
-rw-r--r--src/Networking/Network.h14
-rw-r--r--src/Networking/NetworkDefs.h29
-rw-r--r--src/Networking/NetworkInterface.h6
-rw-r--r--src/Networking/NetworkResponder.cpp4
-rw-r--r--src/Networking/NetworkResponder.h2
-rw-r--r--src/Networking/Socket.h7
-rw-r--r--src/Networking/W5500Ethernet/W5500Interface.cpp32
-rw-r--r--src/Networking/W5500Ethernet/W5500Interface.h13
-rw-r--r--src/Networking/W5500Ethernet/W5500Socket.cpp2
-rw-r--r--src/Networking/W5500Ethernet/Wiznet/Ethernet/W5500/w5500.cpp15
-rw-r--r--src/Networking/W5500Ethernet/Wiznet/Ethernet/W5500/w5500.h40
-rw-r--r--src/Networking/W5500Ethernet/Wiznet/Ethernet/socketlib.cpp45
-rw-r--r--src/Networking/W5500Ethernet/Wiznet/Ethernet/socketlib.h4
-rw-r--r--src/Networking/W5500Ethernet/Wiznet/Ethernet/wizchip_conf.cpp59
-rw-r--r--src/Networking/W5500Ethernet/Wiznet/Ethernet/wizchip_conf.h26
-rw-r--r--src/Networking/W5500Ethernet/Wiznet/Internet/DHCP/dhcp.cpp166
-rw-r--r--src/Networking/W5500Ethernet/Wiznet/Internet/DHCP/dhcp.h8
-rw-r--r--src/ObjectModel/ObjectModel.cpp263
-rw-r--r--src/ObjectModel/ObjectModel.h107
-rw-r--r--src/Pins.h4
-rw-r--r--src/Platform.cpp211
-rw-r--r--src/Platform.h52
-rw-r--r--src/RepRap.cpp27
-rw-r--r--src/RepRap.h12
-rw-r--r--src/RepRapFirmware.cpp7
-rw-r--r--src/Storage/FileStore.cpp2
-rw-r--r--src/Storage/FileStore.h4
-rw-r--r--src/Storage/MassStorage.cpp2
-rw-r--r--src/Tasks.cpp6
-rw-r--r--src/Tasks.h23
-rw-r--r--src/Version.h2
-rw-r--r--src/ZProbe.cpp1
-rw-r--r--src/ZProbe.h7
93 files changed, 2242 insertions, 1561 deletions
diff --git a/.cproject b/.cproject
index dab241d6..c83c06d0 100644
--- a/.cproject
+++ b/.cproject
@@ -67,7 +67,7 @@
<option id="gnu.cpp.link.option.libs.1995000942" name="Libraries (-l)" superClass="gnu.cpp.link.option.libs" useByScannerDiscovery="false" valueType="libs">
<listOptionValue builtIn="false" value="${CoreName}"/>
</option>
- <option id="gnu.cpp.link.option.flags.1670739910" name="Linker flags" superClass="gnu.cpp.link.option.flags" useByScannerDiscovery="false" value="-Os -Wl,--gc-sections -Wl,--fatal-warnings -mcpu=cortex-m3 -T${workspace_loc:/${CoreName}/variants/duet/linker_scripts/gcc/flash.ld} -Wl,-Map,${workspace_loc:/${ProjName}/${ConfigName}}/${BuildArtifactFileBaseName}.map" valueType="string"/>
+ <option id="gnu.cpp.link.option.flags.1670739910" name="Linker flags" superClass="gnu.cpp.link.option.flags" useByScannerDiscovery="false" value="-Os -Wl,--gc-sections -Wl,--fatal-warnings -mcpu=cortex-m3 -T&quot;${workspace_loc:/${CoreName}/variants/duet/linker_scripts/gcc/flash.ld}&quot; -Wl,-Map,&quot;${workspace_loc:/${ProjName}/${ConfigName}}/${BuildArtifactFileBaseName}.map&quot;" valueType="string"/>
<inputType id="cdt.managedbuild.tool.gnu.cpp.linker.input.1491196930" superClass="cdt.managedbuild.tool.gnu.cpp.linker.input">
<additionalInput kind="additionalinputdependency" paths="$(USER_OBJS)"/>
<additionalInput kind="additionalinput" paths="$(LIBS)"/>
@@ -179,7 +179,7 @@
<option id="gnu.cpp.link.option.libs.1006761104" name="Libraries (-l)" superClass="gnu.cpp.link.option.libs" useByScannerDiscovery="false" valueType="libs">
<listOptionValue builtIn="false" value="${CoreName}"/>
</option>
- <option id="gnu.cpp.link.option.flags.827167716" name="Linker flags" superClass="gnu.cpp.link.option.flags" useByScannerDiscovery="false" value="-Os -Wl,--gc-sections -Wl,--fatal-warnings -mcpu=cortex-m3 -T${workspace_loc:/${CoreName}/variants/RADDS/linker_scripts/gcc/flash.ld} -Wl,-Map,${workspace_loc:/${ProjName}/${ConfigName}}/${BuildArtifactFileBaseName}.map" valueType="string"/>
+ <option id="gnu.cpp.link.option.flags.827167716" name="Linker flags" superClass="gnu.cpp.link.option.flags" useByScannerDiscovery="false" value="-Os -Wl,--gc-sections -Wl,--fatal-warnings -mcpu=cortex-m3 -T&quot;${workspace_loc:/${CoreName}/variants/RADDS/linker_scripts/gcc/flash.ld}&quot; -Wl,-Map,&quot;${workspace_loc:/${ProjName}/${ConfigName}}/${BuildArtifactFileBaseName}.map&quot;" valueType="string"/>
<inputType id="cdt.managedbuild.tool.gnu.cpp.linker.input.99895855" superClass="cdt.managedbuild.tool.gnu.cpp.linker.input">
<additionalInput kind="additionalinputdependency" paths="$(USER_OBJS)"/>
<additionalInput kind="additionalinput" paths="$(LIBS)"/>
@@ -294,7 +294,7 @@
<option id="gnu.cpp.link.option.libs.1260510068" name="Libraries (-l)" superClass="gnu.cpp.link.option.libs" useByScannerDiscovery="false" valueType="libs">
<listOptionValue builtIn="false" value="${CoreName}"/>
</option>
- <option id="gnu.cpp.link.option.flags.1376831701" name="Linker flags" superClass="gnu.cpp.link.option.flags" useByScannerDiscovery="false" value="-Os -Wl,--gc-sections -Wl,--fatal-warnings -mcpu=cortex-m3 -T${workspace_loc:/${CoreName}/variants/alligator/linker_scripts/gcc/flash.ld} -Wl,-Map,${workspace_loc:/${ProjName}/${ConfigName}}/${BuildArtifactFileBaseName}.map" valueType="string"/>
+ <option id="gnu.cpp.link.option.flags.1376831701" name="Linker flags" superClass="gnu.cpp.link.option.flags" useByScannerDiscovery="false" value="-Os -Wl,--gc-sections -Wl,--fatal-warnings -mcpu=cortex-m3 -T&quot;${workspace_loc:/${CoreName}/variants/alligator/linker_scripts/gcc/flash.ld&quot; -Wl,-Map,&quot;${workspace_loc:/${ProjName}/${ConfigName}}/${BuildArtifactFileBaseName}.map&quot;" valueType="string"/>
<inputType id="cdt.managedbuild.tool.gnu.cpp.linker.input.1951368129" superClass="cdt.managedbuild.tool.gnu.cpp.linker.input">
<additionalInput kind="additionalinputdependency" paths="$(USER_OBJS)"/>
<additionalInput kind="additionalinput" paths="$(LIBS)"/>
@@ -358,21 +358,21 @@
<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"/>
+ <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"/>
</extensions>
</storageModule>
<storageModule moduleId="cdtBuildSystem" version="4.0.0">
<configuration artifactExtension="elf" artifactName="Duet2CombinedFirmware" buildArtefactType="org.eclipse.cdt.build.core.buildArtefactType.exe" buildProperties="org.eclipse.cdt.build.core.buildArtefactType=org.eclipse.cdt.build.core.buildArtefactType.exe,org.eclipse.cdt.build.core.buildType=org.eclipse.cdt.build.core.buildType.release" cleanCommand="rm -rf" description="" id="cdt.managedbuild.config.gnu.cross.exe.release.516195201.976458850.241502451.170574622" name="Duet2_RTOS" parent="cdt.managedbuild.config.gnu.cross.exe.release" postannouncebuildStep="Generating binary file" postbuildStep="arm-none-eabi-objcopy -O binary ${workspace_loc:/${ProjName}/${ConfigName}}/${BuildArtifactFileBaseName}.elf ${workspace_loc:/${ProjName}/${ConfigName}}/${BuildArtifactFileBaseName}.bin">
<folderInfo id="cdt.managedbuild.config.gnu.cross.exe.release.516195201.976458850.241502451.170574622." name="/" resourcePath="">
- <toolChain id="cdt.managedbuild.toolchain.gnu.cross.exe.release.435431950" name="Cross GCC" superClass="cdt.managedbuild.toolchain.gnu.cross.exe.release">
+ <toolChain id="cdt.managedbuild.toolchain.gnu.cross.exe.release.435431950" name="Cross GCC" nonInternalBuilderId="cdt.managedbuild.builder.gnu.cross" superClass="cdt.managedbuild.toolchain.gnu.cross.exe.release">
<option id="cdt.managedbuild.option.gnu.cross.path.1881231799" name="Path" superClass="cdt.managedbuild.option.gnu.cross.path" useByScannerDiscovery="false" value="${GccPath}" valueType="string"/>
<option id="cdt.managedbuild.option.gnu.cross.prefix.172065168" 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.1838379384" isAbstract="false" osList="all" superClass="cdt.managedbuild.targetPlatform.gnu.cross"/>
- <builder buildPath="${workspace_loc:/RepRapFirmware}/Release" id="cdt.managedbuild.builder.gnu.cross.591414239" keepEnvironmentInBuildfile="false" managedBuildOn="true" name="Gnu Make Builder" parallelBuildOn="true" parallelizationNumber="optimal" superClass="cdt.managedbuild.builder.gnu.cross"/>
+ <builder buildPath="${workspace_loc:/RepRapFirmware}/Duet2_RTOS" id="cdt.managedbuild.builder.gnu.cross.1206198077" keepEnvironmentInBuildfile="false" name="Gnu Make Builder" parallelBuildOn="true" parallelizationNumber="optimal" superClass="cdt.managedbuild.builder.gnu.cross"/>
<tool id="cdt.managedbuild.tool.gnu.cross.assembler.1539163958" name="Cross GCC Assembler" superClass="cdt.managedbuild.tool.gnu.cross.assembler">
<inputType id="cdt.managedbuild.tool.gnu.assembler.input.1036697395" superClass="cdt.managedbuild.tool.gnu.assembler.input"/>
</tool>
@@ -416,7 +416,7 @@
<listOptionValue builtIn="false" value="FreeRTOS"/>
<listOptionValue builtIn="false" value="RRFLibraries"/>
</option>
- <option id="gnu.cpp.link.option.flags.161856294" name="Linker flags" superClass="gnu.cpp.link.option.flags" useByScannerDiscovery="false" value="-Os --specs=nano.specs -Wl,--gc-sections -Wl,--fatal-warnings -mcpu=cortex-m4 -mfpu=fpv4-sp-d16 -mfloat-abi=hard -T${workspace_loc:/${CoreName}/variants/duetNG/linker_scripts/gcc/flash.ld} -Wl,-Map,${workspace_loc:/${ProjName}/${ConfigName}}/${BuildArtifactFileBaseName}.map" valueType="string"/>
+ <option id="gnu.cpp.link.option.flags.161856294" name="Linker flags" superClass="gnu.cpp.link.option.flags" useByScannerDiscovery="false" value="-Os --specs=nano.specs -Wl,--gc-sections -Wl,--fatal-warnings -mcpu=cortex-m4 -mfpu=fpv4-sp-d16 -mfloat-abi=hard -T&quot;${workspace_loc:/${CoreName}/variants/duetNG/linker_scripts/gcc/flash.ld}&quot; -Wl,-Map,&quot;${workspace_loc:/${ProjName}/${ConfigName}}/${BuildArtifactFileBaseName}.map&quot;" valueType="string"/>
<inputType id="cdt.managedbuild.tool.gnu.cpp.linker.input.1270956612" superClass="cdt.managedbuild.tool.gnu.cpp.linker.input">
<additionalInput kind="additionalinputdependency" paths="$(USER_OBJS)"/>
<additionalInput kind="additionalinput" paths="$(LIBS)"/>
@@ -539,7 +539,7 @@
<listOptionValue builtIn="false" value="FreeRTOS"/>
<listOptionValue builtIn="false" value="RRFLibraries"/>
</option>
- <option id="gnu.cpp.link.option.flags.1077151865" name="Linker flags" superClass="gnu.cpp.link.option.flags" useByScannerDiscovery="false" value="-Os --specs=nano.specs -Wl,--gc-sections -Wl,--fatal-warnings -mcpu=cortex-m4 -T${workspace_loc:/${CoreName}/variants/sam4s/linker_scripts/gcc/flash.ld} -Wl,-Map,${workspace_loc:/${ProjName}/${ConfigName}}/${BuildArtifactFileBaseName}.map" valueType="string"/>
+ <option id="gnu.cpp.link.option.flags.1077151865" name="Linker flags" superClass="gnu.cpp.link.option.flags" useByScannerDiscovery="false" value="-Os --specs=nano.specs -Wl,--gc-sections -Wl,--fatal-warnings -mcpu=cortex-m4 -T&quot;${workspace_loc:/${CoreName}/variants/sam4s/linker_scripts/gcc/flash.ld}&quot; -Wl,-Map,&quot;${workspace_loc:/${ProjName}/${ConfigName}}/${BuildArtifactFileBaseName}.map&quot;" valueType="string"/>
<inputType id="cdt.managedbuild.tool.gnu.cpp.linker.input.480654714" superClass="cdt.managedbuild.tool.gnu.cpp.linker.input">
<additionalInput kind="additionalinputdependency" paths="$(USER_OBJS)"/>
<additionalInput kind="additionalinput" paths="$(LIBS)"/>
@@ -672,7 +672,7 @@
<listOptionValue builtIn="false" value="FreeRTOS"/>
<listOptionValue builtIn="false" value="RRFLibraries"/>
</option>
- <option id="gnu.cpp.link.option.flags.2100826215" name="Linker flags" superClass="gnu.cpp.link.option.flags" useByScannerDiscovery="false" value="-Os --specs=nano.specs -Wl,--gc-sections -Wl,--fatal-warnings -mcpu=cortex-m7 -mfpu=fpv5-d16 -mfloat-abi=hard -T${workspace_loc:/${CoreName}/variants/same70/linker_scripts/gcc/flash.ld} -Wl,-Map,${workspace_loc:/${ProjName}/${ConfigName}}/${BuildArtifactFileBaseName}.map" valueType="string"/>
+ <option id="gnu.cpp.link.option.flags.2100826215" name="Linker flags" superClass="gnu.cpp.link.option.flags" useByScannerDiscovery="false" value="-Os --specs=nano.specs -Wl,--gc-sections -Wl,--fatal-warnings -mcpu=cortex-m7 -mfpu=fpv5-d16 -mfloat-abi=hard -T&quot;${workspace_loc:/${CoreName}/variants/same70/linker_scripts/gcc/flash.ld}&quot; -Wl,-Map,&quot;${workspace_loc:/${ProjName}/${ConfigName}}/${BuildArtifactFileBaseName}.map&quot;" valueType="string"/>
<inputType id="cdt.managedbuild.tool.gnu.cpp.linker.input.1623645672" superClass="cdt.managedbuild.tool.gnu.cpp.linker.input">
<additionalInput kind="additionalinputdependency" paths="$(USER_OBJS)"/>
<additionalInput kind="additionalinput" paths="$(LIBS)"/>
@@ -800,7 +800,7 @@
<listOptionValue builtIn="false" value="FreeRTOS"/>
<listOptionValue builtIn="false" value="RRFLibraries"/>
</option>
- <option id="gnu.cpp.link.option.flags.633609481" name="Linker flags" superClass="gnu.cpp.link.option.flags" useByScannerDiscovery="false" value="-Os --specs=nano.specs -Wl,--gc-sections -Wl,--fatal-warnings -mcpu=cortex-m4 -T${workspace_loc:/${CoreName}/variants/sam4s/linker_scripts/gcc/flash.ld} -Wl,-Map,${workspace_loc:/${ProjName}/${ConfigName}}/${BuildArtifactFileBaseName}.map" valueType="string"/>
+ <option id="gnu.cpp.link.option.flags.633609481" name="Linker flags" superClass="gnu.cpp.link.option.flags" useByScannerDiscovery="false" value="-Os --specs=nano.specs -Wl,--gc-sections -Wl,--fatal-warnings -mcpu=cortex-m4 -T&quot;${workspace_loc:/${CoreName}/variants/sam4s/linker_scripts/gcc/flash.ld}&quot; -Wl,-Map,&quot;${workspace_loc:/${ProjName}/${ConfigName}}/${BuildArtifactFileBaseName}.map&quot;" valueType="string"/>
<inputType id="cdt.managedbuild.tool.gnu.cpp.linker.input.96746585" superClass="cdt.managedbuild.tool.gnu.cpp.linker.input">
<additionalInput kind="additionalinputdependency" paths="$(USER_OBJS)"/>
<additionalInput kind="additionalinput" paths="$(LIBS)"/>
@@ -923,7 +923,7 @@
<listOptionValue builtIn="false" value="FreeRTOS"/>
<listOptionValue builtIn="false" value="RRFLibraries"/>
</option>
- <option id="gnu.cpp.link.option.flags.1106600671" name="Linker flags" superClass="gnu.cpp.link.option.flags" useByScannerDiscovery="false" value="-Os --specs=nano.specs -Wl,--gc-sections -Wl,--fatal-warnings -mcpu=cortex-m4 -T${workspace_loc:/${CoreName}/variants/sam4s/linker_scripts/gcc/flash.ld} -Wl,-Map,${workspace_loc:/${ProjName}/${ConfigName}}/${BuildArtifactFileBaseName}.map" valueType="string"/>
+ <option id="gnu.cpp.link.option.flags.1106600671" name="Linker flags" superClass="gnu.cpp.link.option.flags" useByScannerDiscovery="false" value="-Os --specs=nano.specs -Wl,--gc-sections -Wl,--fatal-warnings -mcpu=cortex-m4 -T&quot;${workspace_loc:/${CoreName}/variants/sam4s/linker_scripts/gcc/flash.ld}&quot; -Wl,-Map,&quot;${workspace_loc:/${ProjName}/${ConfigName}}/${BuildArtifactFileBaseName}.map&quot;" valueType="string"/>
<inputType id="cdt.managedbuild.tool.gnu.cpp.linker.input.180173717" superClass="cdt.managedbuild.tool.gnu.cpp.linker.input">
<additionalInput kind="additionalinputdependency" paths="$(USER_OBJS)"/>
<additionalInput kind="additionalinput" paths="$(LIBS)"/>
@@ -1056,7 +1056,7 @@
<listOptionValue builtIn="false" value="FreeRTOS"/>
<listOptionValue builtIn="false" value="RRFLibraries"/>
</option>
- <option id="gnu.cpp.link.option.flags.1694312842" name="Linker flags" superClass="gnu.cpp.link.option.flags" useByScannerDiscovery="false" value="-Os --specs=nano.specs -Wl,--gc-sections -Wl,--fatal-warnings -mcpu=cortex-m7 -mfpu=fpv5-d16 -mfloat-abi=hard -T${workspace_loc:/${CoreName}/variants/same70/linker_scripts/gcc/flash.ld} -Wl,-Map,${workspace_loc:/${ProjName}/${ConfigName}}/${BuildArtifactFileBaseName}.map" valueType="string"/>
+ <option id="gnu.cpp.link.option.flags.1694312842" name="Linker flags" superClass="gnu.cpp.link.option.flags" useByScannerDiscovery="false" value="-Os --specs=nano.specs -Wl,--gc-sections -Wl,--fatal-warnings -mcpu=cortex-m7 -mfpu=fpv5-d16 -mfloat-abi=hard -T&quot;${workspace_loc:/${CoreName}/variants/same70/linker_scripts/gcc/flash.ld}&quot; -Wl,-Map&quot;${workspace_loc:/${ProjName}/${ConfigName}}/${BuildArtifactFileBaseName}.map&quot;" valueType="string"/>
<inputType id="cdt.managedbuild.tool.gnu.cpp.linker.input.806549806" superClass="cdt.managedbuild.tool.gnu.cpp.linker.input">
<additionalInput kind="additionalinputdependency" paths="$(USER_OBJS)"/>
<additionalInput kind="additionalinput" paths="$(LIBS)"/>
@@ -1123,11 +1123,15 @@
<configuration configurationName="DuetM_RTOS"/>
<configuration configurationName="Alligator"/>
<configuration configurationName="SAME70"/>
- <configuration configurationName="Duet2"/>
<configuration configurationName="RADDS"/>
<configuration configurationName="Duet2_RTOS"/>
+ <configuration configurationName="Duet2"/>
+ <configuration configurationName="Duet3"/>
+ <configuration configurationName="PCCB"/>
<configuration configurationName="DuetM"/>
+ <configuration configurationName="PCCB_X5"/>
<configuration configurationName="Duet085"/>
+ <configuration configurationName="SAME70XPLD"/>
</storageModule>
<storageModule moduleId="org.eclipse.cdt.internal.ui.text.commentOwnerProjectMappings"/>
<storageModule moduleId="org.eclipse.cdt.make.core.buildtargets"/>
diff --git a/src/BugList.txt b/src/BugList.txt
index 2b00da7e..94665734 100644
--- a/src/BugList.txt
+++ b/src/BugList.txt
@@ -33,49 +33,87 @@ Implemented in 2.02beta1:
- [done, ok] Attempts to set chopper control registers with invalid TOFF/TBL combinations are rejected
- [done, ok] Support A parameter in M106 command
- [done] Emergency stop terminates all printing files/macros
-- ch change: add support for M703 (run filament config)
-- ch bug fix: if config.g invoked a macro then final values were copied to GCode sources too early and M501 wasn't recognised
-- PCCB build: endstop 0 and 1 are now assigned to Z and X respectively
-- added check for timeout when sending to the W5500 but not receiving
+- [done] ch change: add support for M703 (run filament config)
+- [done] ch bug fix: if config.g invoked a macro then final values were copied to GCode sources too early and M501 wasn't recognised
+- [done] PCCB build: endstop 0 and 1 are now assigned to Z and X respectively
+- [done] added check for timeout when sending to the W5500 but not receiving
-Investigations:
+Done in 2.02RC2:
- [done, test] Fix additional axes on delta not coordinated
- [done] DWC disconnects when a message box and a beep are pending at the same time
+- [done, ok on DuetM, test on Duet2] No warning messages when TMC2224 drivers overheat, https://forum.duet3d.com/topic/6309/little-monster-s-hort-to-ground/13
+- [done] Different numbers of endstop inputs and motor drivers
+- [done, ok] Support mixed stealthchop/spread cycle mode on Maestro via TPWMTHRS register, https://forum.duet3d.com/topic/6512/duet-2-maestro-stealthchop-default/7
+- [done, test] Add paused coordinates to 'printing paused' message? https://reprap.org/forum/read.php?416,832303,832440#msg-832440
+- [done] If a bad curve fit occurs during tuning, display the values as A, C and D instead of G, tc and td to better relate to M307
+- [done, M3D testing] Merge in Matt's display changes
+
+Investigations:
+**- 3 independent Z motors, https://forum.duet3d.com/topic/6974/problem-with-3-independent-z-axis-motors-and-endstops/26
+- incorrect babystepping, https://forum.duet3d.com/topic/6888/babystep-bug-w-incorrect-motion/2 (already fixed 1mm limit)
- [tested, pause/resume works as intended] Check M106 R1 parameter, see https://forum.duet3d.com/topic/6538/resuming-print-fan-after-pause
- M226 not working? https://forum.duet3d.com/topic/6860/filament-change-no-reaction/3
-- spurious drive disconected messages in RC2, https://forum.duet3d.com/topic/6765/firmware-2-02rc2-released/14
- Weird height map, https://forum.duet3d.com/topic/6472/mesh-grid-compensation/28
- Full stepping problem, https://forum.duet3d.com/topic/6433/how-to-reduce-the-speed-of-extrusion/14
- Print time estimation problem, see https://forum.duet3d.com/topic/5572/it-s-out-reprapfirmware-2-0-and-1-21-1-released/64 and https://forum.duet3d.com/topic/5572/it-s-out-reprapfirmware-2-0-and-1-21-1-released/73
- Disconnections, https://forum.duet3d.com/topic/6487/running-bed-mesh-compensation/19
- M122, https://forum.duet3d.com/topic/6725/m122-does-not-work-from-dwc-console
+- DueX5 LEDs flashing at boot time, https://forum.duet3d.com/topic/6970/led-strip-flashing-on-boot-duex5
+- M24 after heater fault pause, https://forum.duet3d.com/topic/7154/firmware-2-01-resume-after-heater-fault-isn-t-working
Remaining:
-- [done, ok on DuetM, test on Duet2] No warning messages when TMC2224 drivers overheat, https://forum.duet3d.com/topic/6309/little-monster-s-hort-to-ground/13
-- [done] Different numbers of endstop inputs and motor drivers
-- [done, ok] Support mixed stealthchop/spread cycle mode on Maestro via TPWMTHRS register, https://forum.duet3d.com/topic/6512/duet-2-maestro-stealthchop-default/7
-- [done, test] Add paused coordinates to 'printing paused' message? https://reprap.org/forum/read.php?416,832303,832440#msg-832440
-- [done] If a bad curve fit occurs during tuning, display the values as A, C and D instead of G, tc and td to better relate to M307
-- [done, M3D testing] Merge in Matt's display changes
-- M918 should echo current settings
-- Limit amount of CPU time used to refesh the display, https://forum.duet3d.com/topic/6676/firmware-2-02-release-candidate-1-now-available
-- Option to generate stall warning messages if stalls occur when not printing from SD card, https://forum.duet3d.com/topic/6720/stall-protection-on-pyserial-print/6
-- Add check digit to serial number
-- check DAA working as intended, results are inconsistent
-- chrishamm's watchdog issue, see his email oif 2018-08-01
-- G30 S-1 when no Z probe, https://forum.duet3d.com/topic/6510/a-couple-of-dwc-odd-things/2
+- [done, test] Zero or negative Z probe tolerance means always average all readings (G30 and G29)
+- [done, test] When storage debug enabled, failing to open a file is a warning not an error
+- [done, test] Improve motor phase open circuit message and make it a warning not an error
+- [done, test] Increase number of restore points from 3 to 4
+- [done, test] G60 to save current tool as well as position
+- [done, test] Allow T R2 etc.
+- [done, ok] M918 should echo current settings (Maestro only)
+- [done, test] Fix Duet 3 map extruders to remote drivers
+- [done, test] Limit amount of CPU time used to refesh the 12864 display, https://forum.duet3d.com/topic/6676/firmware-2-02-release-candidate-1-now-available
+- [done, test] Fixed incorrect check for G2/G3 missing parameter
+- [done, ask Ian to test] Fix CoreXYUV stall detection
+- [done, test] Absolute babystepping should't be restricted to 1mm change, https://forum.duet3d.com/topic/6888/babystep-bug-w-incorrect-motion/2
+- [done, ok I think] CH report that movements don't always start
+- [done, test] Implement M600
+- [done] current loop ADC channel PR
+- [done, test] WiFi auto reconnect
+- [done, ok] Object model preliminary code including M408 P1
+- [done, test] Workplace coordinate Z reading wrong, https://forum.duet3d.com/topic/7187/problem-with-setting-working-coordinate-systems
+- [done, test] Support M208 Xaa:bb Ycc:dd etc.
+- [done, ok] M915 should recognise E parameter
+- [done, ok, also test M20 and M503 - ok] M915 output gets truncated and not terminated, problem for octoprint, https://github.com/dc42/RepRapFirmware/issues/212
+- [increased minimum speed for open load detection] spurious drive disconnected messages in RC2, https://forum.duet3d.com/topic/6765/firmware-2-02rc2-released/14
+- [done, test] M557 option to set number of X and Y points instead of limits and spacing
+- [done, test] support M205 for setting jerk
+- [done, test] Add S parameter to M116 to specify acceptable temperature difference
+- [done] When Z probe type is set to bltouch don't turn Z mod pin on/off at start and end of probing
+- [done, test] Allow endstop input number to be specified in M558
+- [done, ok] G30 S-1 when no Z probe, https://forum.duet3d.com/topic/6510/a-couple-of-dwc-odd-things/2
+- [done] Log Z leadscrew/manual adjustment calibration results even if calibration failed
+- [done] Log mesh probing results to file
+
+- [no fault located, re-test] Fix Duet 3 ABC axes
+- [no fault located, re-test] Wait for all moves to stop before M584
+- check DAA working as intended, results are inconsistent. Problem when used with segmented kinematics because the acceleration is in multiple segments.
+- Allow extruder movement in tpre? https://forum.duet3d.com/topic/7263/controlling-stepper-motors-via-drive-numbers-eg-g1-d4-700-f100/4
+- [no, it already adds 22 checksum bits] Add check digit to serial number
+- [no, we don't record print time] Distinguish between estimated/simulated/actual print time in M36
+- M207 per-tool values, https://forum.duet3d.com/topic/6855/add-drive-extruder-parameter-to-m207/6
+- [problem gone away] chrishamm's watchdog issue, see his email of 2018-08-01
- Command to copy output from the following commands to the log file?
- Track which devices use which pins
- Hangprinter PRs
- PR to have any enabled driver report 50C
-- PR to allow endstop input number to be specified in M558
- M116 parameter to set allowed temperature difference
-- M208 xaa:bb etc.
-- M557 option to set number of X and Y points instead of limits and spacing
- Alternative G10 command to set offsets from known current tool position, see https://forum.duet3d.com/topic/6465/g92-g10-m585-for-setting-head-position-not-machine-position/4
- Keep sending M408 responses to PanelDue while waiting for movement to complete, or M400 or homing move or similar
- CNC shutdown when movement outside limits attempted not working well, https://forum.duet3d.com/topic/6186/stable-firmware-2-01-duet-2-and-1-22-duet-06-085-released/55
+
+Future:
+- Extra logging? https://forum.duet3d.com/topic/7103/extend-m929-logging-capabilities/5
- Junction deviation instead of jerk?
+- first layer segmentation, to help with baby stepping? Or another way to implement live babystepping?
- Still doesn't always find the DueX5, see https://forum.duet3d.com/topic/6239/unstable-after-firmware-upgrade/3. Is the Heat task affecting the timing? Need new I2C driver?
- [do in DuetWiFiServer] WiFi continuous auto reconnect in client mode, or extra M552 parameter? See https://forum.duet3d.com/topic/5765/wifi-module-auto-reconnect
- Better dead time measurement during auto tuning. Measure both turn-on and turn-off?
@@ -85,6 +123,7 @@ Remaining:
- Look at pushover notification support, https://forum.duet3d.com/topic/169/notification-via-pushover-or-other-service/45
- M3 R parameter so it can restore the spinder/laser after a pause (https://forum.duet3d.com/topic/5418/cnc-laser-m3-unpause-r-parameter)
- M81: don't give low voltage warnings when main power has just been turned off
+- M81: option to invert polarity?
- M584 when assigning a drive, unmap any existing assignment? [sometimes we want dual mapping] Also allow an axis to be mapped to driver -1.
- Add S4 option to G1 command, like S1 but no endstop checks (needed for CoreXY, CoreXZ)
- CNC: look at G17/18/19, see https://forum.duet3d.com/topic/4669/ooznest-workbee-screw-driven
@@ -94,14 +133,13 @@ Remaining:
- M140 command to set default bed heaters for M140 S commands (e.g. M140 P0:1:2)
- Consider: Heater faults to run M81 even when not doing a build (https://forum.duet3d.com/topic/6225/configure-action-on-heater-fault/7)
- Option to repeat G32 until deviation/leadscrew adjustment is below a threshold or a retry count reached (and allow for probing failures)
+- Macro option when a motor stall is detected, https://forum.duet3d.com/topic/7026/more-options-for-stall-detection
Other (some of these may be in 2.02):
- Update PanelDue firmware via Duet
- Use Heat task to read DHT sensors?
- Add option R4 to M915 command, to do an emergency stop (useful for Z motor)
- GCodes corresponding to rr_move and rr_mkdir, https://forum.duet3d.com/topic/5470/firmware-2-0rc6-and-1-21-1rc6-released/13
-- Add parameter to M116 to specify acceptable temperature difference
-- support M205 for setting jerk
- support G12 clean tool?
- Add fan PWM limit, https://forum.duet3d.com/topic/5370/m106-feature-request-limit-max-pwm-parameter/4
- after homing, warn if outside M208 movement limits on SCARA, polar etc.
@@ -116,6 +154,8 @@ Other (some of these may be in 2.02):
- At the end of a simulation, restore the original workplace coordinate selection
- Add warning message when print exceeds bounds
- When uploading while a file is being printed, don't allow the currently-printing file to be replaced
+- Option to send stall warning messages when not printing from SD card, https://forum.duet3d.com/topic/6720/stall-protection-on-pyserial-print
+- Custom macros to execute on stall detection, including extruder stall detection https://forum.duet3d.com/topic/6730/stall-detection-custom-actions
- [check] if a homing command in an SD print file is aborted due to e.g. G1 Z5 in the homing file, error message should be written to both DWC and PanelDue
- [no fault] stall detect on Z axis
diff --git a/src/Configuration.h b/src/Configuration.h
index ee193699..c29f882d 100644
--- a/src/Configuration.h
+++ b/src/Configuration.h
@@ -208,7 +208,7 @@ constexpr float SILLY_Z_VALUE = -9999.0; // Millimetres
// String lengths
constexpr size_t FORMAT_STRING_LENGTH = 256;
constexpr size_t MACHINE_NAME_LENGTH = 40;
-constexpr size_t PASSWORD_LENGTH = 20;
+constexpr size_t PASSWORD_LENGTH = 20; // must also be long enough to hold any homing file name
#if SAM4E || SAM4S || SAME70
// Increased GCODE_LENGTH on the SAM4 because M587 and M589 commands on the Duet WiFi can get very long
@@ -223,8 +223,10 @@ constexpr size_t MaxMessageLength = 256;
#if SAM4E || SAM4S || SAME70
constexpr size_t MaxFilenameLength = 120; // Maximum length of a filename including the path
+constexpr size_t MaxVariableNameLength = 120;
#else
constexpr size_t MaxFilenameLength = 100;
+constexpr size_t MaxVariableNameLength = 100;
#endif
constexpr size_t MaxHeaterNameLength = 20; // Maximum number of characters in a heater name
@@ -265,7 +267,7 @@ constexpr uint32_t DefaultIdleTimeout = 30000; // Milliseconds
constexpr float DefaultIdleCurrentFactor = 0.3; // Proportion of normal motor current that we use for idle hold
constexpr float DefaultNonlinearExtrusionLimit = 0.2; // Maximum additional commanded extrusion to compensate for nonlinearity
-constexpr size_t NumRestorePoints = 3; // Number of restore points, must be at least 3
+constexpr size_t NumRestorePoints = 6; // Number of restore points, must be at least 3
// Triggers
constexpr unsigned int MaxTriggers = 10; // Must be <= 32 because we store a bitmap of pending triggers in a uint32_t
diff --git a/src/Display/Display.cpp b/src/Display/Display.cpp
index 195cd9f2..094a7cad 100644
--- a/src/Display/Display.cpp
+++ b/src/Display/Display.cpp
@@ -21,9 +21,11 @@ const LcdFont& smallFont = font7x11;
const LcdFont& largeFont = font11x14;
const LcdFont * const fonts[] = { &font7x11, &font11x14 };
+const size_t SmallFontNumber = 0;
+const size_t LargeFontNumber = 1;
Display::Display()
- : lcd(LcdCSPin), encoder(EncoderPinA, EncoderPinB, EncoderPinSw), menu(lcd, fonts, ARRAY_SIZE(fonts)), present(false), beepActive(false), updatingFirmware(false)
+ : lcd(LcdCSPin, fonts, ARRAY_SIZE(fonts)), encoder(EncoderPinA, EncoderPinB, EncoderPinSw), menu(lcd), present(false), beepActive(false), updatingFirmware(false)
{
}
@@ -36,7 +38,7 @@ void Display::Init()
void Display::Start()
{
- lcd.SetFont(&smallFont);
+ lcd.SetFont(SmallFontNumber);
menu.Load("main");
}
@@ -48,7 +50,7 @@ void Display::Spin(bool full)
{
if (!updatingFirmware)
{
- // Check encoder and update display here
+ // Check encoder and update display
const int ch = encoder.GetChange();
if (ch != 0)
{
@@ -77,7 +79,7 @@ void Display::Exit()
{
lcd.TextInvert(false);
lcd.Clear();
- lcd.SetFont(&largeFont);
+ lcd.SetFont(LargeFontNumber);
lcd.SetCursor(20, 0);
lcd.print("Shutting down...");
}
@@ -115,6 +117,14 @@ GCodeResult Display::Configure(GCodeBuffer& gb, const StringRef& reply)
encoder.Init(gb.GetIValue()); // configure encoder pulses per click and direction
}
}
+ else if (!present)
+ {
+ reply.copy("12864 display is not present or not configured");
+ }
+ else
+ {
+ reply.printf("12864 display is configured, pulses-per-click is %d", encoder.GetPulsesPerClick());
+ }
return GCodeResult::ok;
}
@@ -125,7 +135,7 @@ void Display::UpdatingFirmware()
IoPort::WriteAnalog(LcdBeepPin, 0.0, 0); // stop any beep
lcd.TextInvert(false);
lcd.Clear();
- lcd.SetFont(&largeFont);
+ lcd.SetFont(LargeFontNumber);
lcd.SetCursor(20, 0);
lcd.print("Updating firmware...");
lcd.FlushAll();
diff --git a/src/Display/Menu.cpp b/src/Display/Menu.cpp
index 1a30cc99..d5634847 100644
--- a/src/Display/Menu.cpp
+++ b/src/Display/Menu.cpp
@@ -79,8 +79,8 @@
const uint32_t InactivityTimeout = 20000; // inactivity timeout
const uint32_t ErrorTimeout = 6000; // how long wre display an error message for
-Menu::Menu(Lcd7920& refLcd, const LcdFont * const fnts[], size_t nFonts)
- : lcd(refLcd), fonts(fnts), numFonts(nFonts),
+Menu::Menu(Lcd7920& refLcd)
+ : lcd(refLcd),
timeoutValue(0), lastActionTime(0),
selectableItems(nullptr), unSelectableItems(nullptr), numNestedMenus(0), numSelectableItems(0), highlightedItem(0), itemIsSelected(false), displayingFixedMenu(false),
errorColumn(0), rowOffset(0)
@@ -173,7 +173,7 @@ void Menu::LoadError(const char *msg, unsigned int line)
ResetCache();
lcd.Clear(currentMargin, currentMargin, NumRows - currentMargin, NumCols - currentMargin);
- lcd.SetFont(fonts[0]);
+ lcd.SetFont(0);
lcd.print("Error loading menu\nFile: ");
lcd.print((numNestedMenus > 0) ? filenames[numNestedMenus - 1].c_str() : "(none)");
if (line != 0)
@@ -251,7 +251,7 @@ const char *Menu::ParseMenuLine(char * const commandWord)
break;
case 'F':
- fontNumber = min<unsigned int>(SafeStrtoul(args, &args), numFonts - 1);
+ fontNumber = min<unsigned int>(SafeStrtoul(args, &args), lcd.GetNumFonts() - 1);
break;
case 'V':
@@ -309,7 +309,7 @@ const char *Menu::ParseMenuLine(char * const commandWord)
if (pNewItem->Visible())
{
- lcd.SetFont(fonts[fontNumber]);
+ lcd.SetFont(fontNumber);
lcd.print(text);
row = lcd.GetRow() - currentMargin;
column = lcd.GetColumn() - currentMargin;
@@ -317,23 +317,24 @@ const char *Menu::ParseMenuLine(char * const commandWord)
}
else if (StringEquals(commandWord, "image") && fname != nullptr)
{
- LoadImage(fname);
+ ImageMenuItem *pNewItem = new ImageMenuItem(row, column, fname);
+ AddItem(pNewItem, false);
+ column += pNewItem->GetWidth();
}
else if (StringEquals(commandWord, "button"))
{
const char * const textString = AppendString(text);
const char * const actionString = AppendString(action);
- const char *const c_acFileString = AppendString(fname);
+ const char * const c_acFileString = AppendString(fname);
MenuItem::CheckFunction bF = &(Menu::CheckVisibility);
ButtonMenuItem *pNewItem = new ButtonMenuItem(row, column, fontNumber, xVis, bF, textString, actionString, c_acFileString);
AddItem(pNewItem, true);
- // Print the button as well so that we can update the row and column
+ // Print the button as well so that we can update the column
if (pNewItem->Visible())
{
- lcd.SetFont(fonts[fontNumber]);
+ lcd.SetFont(fontNumber);
lcd.print(text);
- row = lcd.GetRow() - currentMargin;
column = lcd.GetColumn() - currentMargin;
}
}
@@ -352,8 +353,8 @@ const char *Menu::ParseMenuLine(char * const commandWord)
const char * const actionString = AppendString(action);
const char *const dir = AppendString(dirpath);
const char *const acFileString = AppendString(fname);
- AddItem(new FilesMenuItem(row, 0, fontNumber, actionString, dir, acFileString, nparam, fonts[fontNumber]->height), true);
- row += nparam * fonts[fontNumber]->height;
+ AddItem(new FilesMenuItem(row, 0, fontNumber, actionString, dir, acFileString, nparam), true);
+ row += nparam * lcd.GetFontHeight(fontNumber);
column = 0;
}
else
@@ -454,7 +455,7 @@ const char *Menu::AppendString(const char *s)
const size_t oldIndex = commandBufferIndex;
if (commandBufferIndex < sizeof(commandBuffer))
{
- SafeStrncpy(commandBuffer + commandBufferIndex, s, sizeof(commandBuffer) - commandBufferIndex);
+ SafeStrncpy(commandBuffer + commandBufferIndex, s, ARRAY_SIZE(commandBuffer) - commandBufferIndex);
commandBufferIndex += strlen(commandBuffer + commandBufferIndex) + 1;
}
return commandBuffer + oldIndex;
@@ -502,12 +503,9 @@ void Menu::EncoderAction_EnterItemHelper()
int nNextCommandIndex = StringContains(pcCurrentCommand, "|");
while (-1 != nNextCommandIndex)
{
- *(pcCurrentCommand + nNextCommandIndex - 1) = '\0';
-
+ *(pcCurrentCommand + nNextCommandIndex) = '\0';
EncoderAction_ExecuteHelper(pcCurrentCommand);
-
- pcCurrentCommand += nNextCommandIndex;
-
+ pcCurrentCommand += nNextCommandIndex + 1;
nNextCommandIndex = StringContains(pcCurrentCommand, "|");
}
EncoderAction_ExecuteHelper(pcCurrentCommand);
@@ -531,7 +529,7 @@ void Menu::EncoderAction_AdjustItemHelper(int action)
// Let the current menu item attempt to handle scroll wheel first
action = oStartItem->Advance(action);
- if (0 != action)
+ if (action != 0)
{
// Otherwise we move through the remaining selectable menu items
highlightedItem += action;
@@ -545,15 +543,24 @@ void Menu::EncoderAction_AdjustItemHelper(int action)
}
// Let the newly selected MenuItem handle any selection setup
- MenuItem *const oNewItem = FindHighlightedItem();
+ MenuItem * const oNewItem = FindHighlightedItem();
oNewItem->Enter(action > 0);
PixelNumber tLastOffset = rowOffset;
- rowOffset = oNewItem->GetVisibilityRowOffset(tLastOffset, fonts[oNewItem->GetFontNumber()]);
+ rowOffset = oNewItem->GetVisibilityRowOffset(tLastOffset, lcd.GetFontHeight(oNewItem->GetFontNumber()));
if (rowOffset != tLastOffset)
{
+ // We have scrolled the whole menu, so redraw it
lcd.Clear();
+ for (MenuItem *item = selectableItems; item != nullptr; item = item->GetNext())
+ {
+ item->SetChanged();
+ }
+ for (MenuItem *item = unSelectableItems; item != nullptr; item = item->GetNext())
+ {
+ item->SetChanged();
+ }
}
}
}
@@ -584,16 +591,23 @@ void Menu::EncoderAction(int action)
if (numSelectableItems != 0)
{
if (itemIsSelected) // send the wheel action (scroll or click) to the item itself
+ {
EncoderAction_ExitItemHelper(action);
+ }
else if (action != 0) // scroll without an item under selection
+ {
EncoderAction_AdjustItemHelper(action);
+ }
else // click without an item under selection
+ {
EncoderAction_EnterItemHelper();
+ }
}
lastActionTime = millis();
timeoutValue = InactivityTimeout;
}
+
/*static*/ const char *Menu::SkipWhitespace(const char *s)
{
while (*s == ' ' || *s == '\t')
@@ -612,12 +626,6 @@ void Menu::EncoderAction(int action)
return s;
}
-void Menu::LoadImage(const char *fname)
-{
- //TODO
- lcd.print("[img]");
-}
-
// Refresh is called every Spin() of the Display under most circumstances; an appropriate place to check if timeout action needs to be taken
void Menu::Refresh()
{
@@ -625,8 +633,7 @@ void Menu::Refresh()
{
if (!displayingFixedMenu)
{
- // When the SD card is not mounted, we show a fixed menu for graceful recovery
- LoadFixedMenu();
+ LoadFixedMenu(); // when the SD card is not mounted, we show a fixed menu for graceful recovery
}
}
else if (displayingFixedMenu || (timeoutValue != 0 && (millis() - lastActionTime > timeoutValue)))
@@ -635,7 +642,6 @@ void Menu::Refresh()
// Go to the top menu (just discard information)
numNestedMenus = 0;
Load("main");
-
timeoutValue = 0;
}
@@ -644,18 +650,13 @@ void Menu::Refresh()
for (MenuItem *item = selectableItems; item != nullptr; item = item->GetNext())
{
- // TODO: move this into the item Draw() routine
- lcd.SetFont(fonts[item->GetFontNumber()]);
item->Draw(lcd, rightMargin, (nItemBeingDrawnIndex == highlightedItem), rowOffset);
++nItemBeingDrawnIndex;
}
for (MenuItem *item = unSelectableItems; item != nullptr; item = item->GetNext())
{
- // TODO: move this into the item Draw() routine
- lcd.SetFont(fonts[item->GetFontNumber()]);
item->Draw(lcd, rightMargin, false, rowOffset);
- // ++nItemBeingDrawnIndex; // unused
}
}
diff --git a/src/Display/Menu.h b/src/Display/Menu.h
index 925338f1..16090c94 100644
--- a/src/Display/Menu.h
+++ b/src/Display/Menu.h
@@ -15,7 +15,7 @@
class Menu
{
public:
- Menu(Lcd7920& refLcd, const LcdFont * const fnts[], size_t nFonts);
+ Menu(Lcd7920& refLcd);
void Load(const char* filename); // load a menu file
void Pop();
void EncoderAction(int action);
@@ -29,7 +29,6 @@ private:
void LoadError(const char *msg, unsigned int line);
void AddItem(MenuItem *item, bool isSelectable);
const char *AppendString(const char *s);
- void LoadImage(const char *fname);
MenuItem *FindHighlightedItem() const;
void EncoderAction_EnterItemHelper();
@@ -50,8 +49,6 @@ private:
static const PixelNumber DefaultNumberWidth = 20; // default numeric field width
Lcd7920& lcd;
- const LcdFont * const *fonts;
- const size_t numFonts;
uint32_t timeoutValue; // how long to time out after 0 = no timeout
uint32_t lastActionTime;
diff --git a/src/Display/MenuItem.cpp b/src/Display/MenuItem.cpp
index 842e24bd..2caa722e 100644
--- a/src/Display/MenuItem.cpp
+++ b/src/Display/MenuItem.cpp
@@ -16,7 +16,7 @@
#include "Networking/Network.h"
MenuItem::MenuItem(PixelNumber r, PixelNumber c, FontNumber fn)
- : row(r), column(c), fontNumber(fn), next(nullptr)
+ : row(r), column(c), fontNumber(fn), itemChanged(true), highlighted(false), next(nullptr)
{
}
@@ -30,8 +30,6 @@ MenuItem::MenuItem(PixelNumber r, PixelNumber c, FontNumber fn)
*root = item;
}
-TextMenuItem *TextMenuItem::freelist = nullptr;
-
TextMenuItem::TextMenuItem(PixelNumber r, PixelNumber c, FontNumber fn, Visibility xVis, CheckFunction bF, const char* t)
: MenuItem(r, c, fn), text(t), m_xVisCase(xVis), m_bF(bF)
{
@@ -44,32 +42,18 @@ bool TextMenuItem::Visible() const
void TextMenuItem::Draw(Lcd7920& lcd, PixelNumber rightMargin, bool highlight, PixelNumber tOffset)
{
- if (Visible())
+ // We ignore the 'highlight' parameter because text items are not selectable
+ if (Visible() && itemChanged)
{
+ lcd.SetFont(fontNumber);
lcd.SetCursor(row - tOffset, column);
- // lcd.SetRightMargin(rightMargin);
-
+ lcd.SetRightMargin(rightMargin);
lcd.TextInvert(false);
lcd.print(text);
-
- // lcd.SetCursor(row + currentMargin, column + currentMargin);
- // lcd.SetFont(fonts[fontNumber]);
- // lcd.print(text);
- // row = lcd.GetRow() - currentMargin;
- // column = lcd.GetColumn() - currentMargin;
-
- // lcd.ClearToMargin();
+ itemChanged = false;
}
}
-// TODO need to clean up this design since it isn't meaningful to select a text item
-const char* TextMenuItem::Select()
-{
- return text;
-}
-
-ButtonMenuItem *ButtonMenuItem::freelist = nullptr;
-
ButtonMenuItem::ButtonMenuItem(PixelNumber r, PixelNumber c, FontNumber fn, Visibility xVis, CheckFunction bF, const char* t, const char* cmd, char const* acFile)
: MenuItem(r, c, fn), text(t), command(cmd), m_acFile(acFile), m_xVisCase(xVis), m_bF(bF)
{
@@ -83,8 +67,9 @@ bool ButtonMenuItem::Visible() const
void ButtonMenuItem::Draw(Lcd7920& lcd, PixelNumber rightMargin, bool highlight, PixelNumber tOffset)
{
- if (Visible() && column < NumCols)
+ if (Visible() && (itemChanged || highlight != highlighted) && column < NumCols)
{
+ lcd.SetFont(fontNumber);
lcd.SetCursor(row - tOffset, column);
lcd.SetRightMargin(rightMargin);
@@ -93,6 +78,8 @@ void ButtonMenuItem::Draw(Lcd7920& lcd, PixelNumber rightMargin, bool highlight,
lcd.TextInvert(false);
lcd.ClearToMargin();
+ itemChanged = false;
+ highlighted = highlight;
}
}
@@ -101,31 +88,27 @@ void ButtonMenuItem::Draw(Lcd7920& lcd, PixelNumber rightMargin, bool highlight,
// NOTE: menu names must not begin with 'G', 'M' or 'T'
const char* ButtonMenuItem::Select()
{
- m_acCommand[0] = '\0';
-
- SafeStrncpy(m_acCommand, command, strlen(command) + 1);
- // WS1 assumed safe
-
- int nReplacementIndex = StringContains(m_acCommand, "menu");
+ const int nReplacementIndex = StringContains(command, "menu");
if (-1 != nReplacementIndex)
{
- nReplacementIndex -= strlen("menu");
-
- // TODO WS1
- SafeStrncpy(m_acCommand + nReplacementIndex, m_acFile, min(strlen(m_acFile) + 1, sizeof(m_acCommand) - nReplacementIndex));
+ m_acCommand.copy(command, nReplacementIndex);
+ m_acCommand.cat(m_acFile);
+ }
+ else
+ {
+ m_acCommand.copy(command);
}
- return m_acCommand;
+ return m_acCommand.c_str();
}
-PixelNumber ButtonMenuItem::GetVisibilityRowOffset(PixelNumber tCurrentOffset, const LcdFont *oFont) const
+PixelNumber ButtonMenuItem::GetVisibilityRowOffset(PixelNumber tCurrentOffset, PixelNumber fontHeight) const
{
PixelNumber tOffsetRequest = tCurrentOffset;
// Are we off the bottom of the visible window?
- if (64 + tCurrentOffset <= row + oFont->height + 1)
+ if (64 + tCurrentOffset <= row + fontHeight + 1)
{
- // tOffsetRequest = tCurrentOffset + row - 3;
tOffsetRequest = row - 3;
}
@@ -145,14 +128,13 @@ ValueMenuItem::ValueMenuItem(PixelNumber r, PixelNumber c, FontNumber fn, PixelN
void ValueMenuItem::Draw(Lcd7920& lcd, PixelNumber rightMargin, bool highlight, PixelNumber tOffset)
{
- lcd.SetCursor(row - tOffset, column);
- lcd.SetRightMargin(min<PixelNumber>(column + width, rightMargin));
- lcd.TextInvert(highlight);
-
+ lcd.SetFont(fontNumber);
bool error = false;
if (!adjusting)
{
const unsigned int itemNumber = valIndex % 100;
+ const float oldValue = currentValue;
+
switch (valIndex/100)
{
case 0: // heater current temperature
@@ -236,19 +218,19 @@ void ValueMenuItem::Draw(Lcd7920& lcd, PixelNumber rightMargin, bool highlight,
// Platform's IP address is the "planned", Network's IP address is the "actual"
case 30:
- currentValue = reprap.GetNetwork().GetIPAddress(0)[0];
+ currentValue = reprap.GetNetwork().GetIPAddress(0).GetQuad(0);
break;
case 31:
- currentValue = reprap.GetNetwork().GetIPAddress(0)[1];
+ currentValue = reprap.GetNetwork().GetIPAddress(0).GetQuad(1);
break;
case 32:
- currentValue = reprap.GetNetwork().GetIPAddress(0)[2];
+ currentValue = reprap.GetNetwork().GetIPAddress(0).GetQuad(2);
break;
case 33:
- currentValue = reprap.GetNetwork().GetIPAddress(0)[3];
+ currentValue = reprap.GetNetwork().GetIPAddress(0).GetQuad(3);
break;
default:
@@ -260,17 +242,31 @@ void ValueMenuItem::Draw(Lcd7920& lcd, PixelNumber rightMargin, bool highlight,
error = true;
break;
}
- }
- if (error)
- {
- lcd.print("***");
+ if (error || currentValue != oldValue)
+ {
+ itemChanged = true;
+ }
}
- else
+
+ if (itemChanged || (highlight != highlighted))
{
- lcd.print(currentValue, decimals);
+ lcd.SetCursor(row - tOffset, column);
+ lcd.SetRightMargin(min<PixelNumber>(column + width, rightMargin));
+ lcd.TextInvert(highlight);
+
+ if (error)
+ {
+ lcd.print("***");
+ }
+ else
+ {
+ lcd.print(currentValue, decimals);
+ }
+ lcd.ClearToMargin();
+ itemChanged = false;
+ highlighted = highlight;
}
- lcd.ClearToMargin();
}
const char* ValueMenuItem::Select()
@@ -279,7 +275,7 @@ const char* ValueMenuItem::Select()
return nullptr;
}
-PixelNumber ValueMenuItem::GetVisibilityRowOffset(PixelNumber tCurrentOffset, const LcdFont *oFont) const
+PixelNumber ValueMenuItem::GetVisibilityRowOffset(PixelNumber tCurrentOffset, PixelNumber fontHeight) const
{
// TODO
return 0;
@@ -293,19 +289,17 @@ bool ValueMenuItem::Adjust_SelectHelper()
switch (valIndex/100)
{
case 1: // heater active temperature
+ if (1 > currentValue) // 0 is off
{
- if (1 > currentValue) // 0 is off
- {
- reprap.GetGCodes().SetItemActiveTemperature(itemNumber, -273.15f);
- }
- else // otherwise ensure the tool is made active at the same time (really only matters for 79)
+ reprap.GetGCodes().SetItemActiveTemperature(itemNumber, -273.15f);
+ }
+ else // otherwise ensure the tool is made active at the same time (really only matters for 79)
+ {
+ if (80 > itemNumber)
{
- if (80 > itemNumber)
- {
- reprap.SelectTool(itemNumber, false);
- }
- reprap.GetGCodes().SetItemActiveTemperature(itemNumber, currentValue);
+ reprap.SelectTool(itemNumber, false);
}
+ reprap.GetGCodes().SetItemActiveTemperature(itemNumber, currentValue);
}
break;
@@ -385,9 +379,10 @@ bool ValueMenuItem::Adjust_AlterHelper(int clicks)
if (0 > clicks) // decrementing
{
currentValue += clicks;
-
if (95 > (int)currentValue)
+ {
currentValue = 0;
+ }
}
else // incrementing
{
@@ -396,7 +391,6 @@ bool ValueMenuItem::Adjust_AlterHelper(int clicks)
currentValue = (95 - 1);
// --clicks;
}
-
currentValue = min<int>(currentValue + clicks, reprap.GetHeat().GetHighestTemperatureLimit(reprap.GetTool(itemNumber)->Heater(0)));
}
}
@@ -473,20 +467,17 @@ bool ValueMenuItem::Adjust(int clicks)
return Adjust_AlterHelper(clicks);
}
-FilesMenuItem *FilesMenuItem::freelist = nullptr;
-
-FilesMenuItem::FilesMenuItem(PixelNumber r, PixelNumber c, FontNumber fn, const char *cmd, const char *dir, const char *acFile, unsigned int nf, unsigned int uFontHeight)
- : MenuItem(r, c, fn), command(cmd), initialDirectory(dir), m_acFile(acFile), m_uDisplayLines(nf), m_uFontHeight(uFontHeight),
+FilesMenuItem::FilesMenuItem(PixelNumber r, PixelNumber c, FontNumber fn, const char *cmd, const char *dir, const char *acFile, unsigned int nf)
+ : MenuItem(r, c, fn), numDisplayLines(nf), command(cmd), initialDirectory(dir), m_acFile(acFile),
m_uListingFirstVisibleIndex(0), m_uListingSelectedIndex(0), m_oMS(reprap.GetPlatform().GetMassStorage())
{
- m_acCommand[0] = '\0';
-
// There's no guarantee that initialDirectory has a trailing '/'
- SafeStrncpy(m_acCurrentDirectory, initialDirectory, strlen(initialDirectory) + 1);
- // WS1 assumed safe
- if ('/' != m_acCurrentDirectory[strlen(m_acCurrentDirectory) - 1])
- SafeStrncpy(m_acCurrentDirectory + strlen(m_acCurrentDirectory), "/", 2);
- // WS1 assumed safe
+ m_acCurrentDirectory.copy(initialDirectory);
+ const size_t len = m_acCurrentDirectory.strlen();
+ if (len == 0 || '/' != m_acCurrentDirectory[len - 1])
+ {
+ m_acCurrentDirectory.cat('/');
+ }
// We don't bother with m_uHardItemsInDirectory in init. list because --
EnterDirectory();
@@ -501,11 +492,10 @@ void FilesMenuItem::vResetViewState()
void FilesMenuItem::EnterDirectory()
{
vResetViewState();
-
m_uHardItemsInDirectory = 0;
FileInfo oFileInfo;
- if (m_oMS->FindFirst(m_acCurrentDirectory, oFileInfo))
+ if (m_oMS->FindFirst(m_acCurrentDirectory.c_str(), oFileInfo))
{
do
{
@@ -517,14 +507,15 @@ void FilesMenuItem::EnterDirectory()
bool FilesMenuItem::bInSubdirectory() const
{
- const char *pcPathElement = m_acCurrentDirectory;
+ const char *pcPathElement = m_acCurrentDirectory.c_str();
unsigned int uNumSlashes = 0;
while ('\0' != *pcPathElement)
{
if (('/' == *pcPathElement) && ('\0' != *(pcPathElement + 1))) // don't count a trailing slash
+ {
++uNumSlashes;
-
+ }
++pcPathElement;
}
@@ -538,181 +529,149 @@ unsigned int FilesMenuItem::uListingEntries() const
void FilesMenuItem::Draw(Lcd7920& lcd, PixelNumber rightMargin, bool highlight, PixelNumber tOffset)
{
- lcd.SetCursor(row, column); // TODO: consider tOffset
- lcd.SetRightMargin(rightMargin);
-
- if (bInSubdirectory()) // manually add the ".." entry
+ // The 'highlight' parameter is not used to highlight this item, but it is still used to tell whether this item is selected or not
+ if (itemChanged || highlighted != highlight)
{
- // We are writing text to line numbers (0), 1, 2 ... m_uDisplayLines - 1 (0 = "..")
- // If m_uListingFirstVisibleIndex is 0, then we can see "..":
- // The remaining fs entries are m_uListingFirstVisibleIndex, m_uListingFirstVisibleIndex + 1 ... m_uListingFirstVisibleIndex + m_uDisplayLines - 2
- // Otherwise (m_uListingFirstVisibleIndex is not 0, so we can't see "..")
- // The fs entries are m_uListingFirstVisibleIndex, m_uListingFirstVisibleIndex + 1 ... m_uListingFirstVisibleIndex + m_uDisplayLines - 1
- // (We iterate the file system exactly the same, we just use 'i' to make sure we stop at the appropriate time.)
-
- uint8_t i = 0;
-
- // e.g. m_uListingFirstVisible = 0, we'll see "..", "a.gcode", "b.gcode", ...
- // m_uListingFirstVisible = 1, we'll see "a.gcode", "b.gcode", ...
- if (0 == m_uListingFirstVisibleIndex)
- {
- lcd.SetCursor(row, column);
+ lcd.SetFont(fontNumber);
+ lcd.SetRightMargin(rightMargin);
+ uint8_t line = 0;
- if (highlight && (m_uListingSelectedIndex == m_uListingFirstVisibleIndex))
+ // If we are in a subdirectory then we prepend ".." to the list of files
+ unsigned int dirEntriesToSkip;
+ if (bInSubdirectory())
+ {
+ if (m_uListingFirstVisibleIndex == 0)
{
- lcd.print("> ");
+ lcd.SetCursor(row, column);
+ lcd.print(" ..");
+ lcd.ClearToMargin();
+ if (highlight && m_uListingSelectedIndex == 0)
+ {
+ // Overwriting the initial spaces with '>' avoids shifting the following text when we change the selection
+ lcd.SetCursor(row, column);
+ lcd.print(">");
+ }
+ line = 1;
+ dirEntriesToSkip = 0;
}
else
{
- lcd.print(" ");
+ dirEntriesToSkip = m_uListingFirstVisibleIndex - 1;
}
- lcd.print("..");
-
- lcd.ClearToMargin();
-
- i = 1;
+ }
+ else
+ {
+ dirEntriesToSkip = m_uListingFirstVisibleIndex;
}
// Seek to the first file that is in view
- int nDirReferencedLocation = -1;
FileInfo oFileInfo;
- if (m_oMS->FindFirst(m_acCurrentDirectory, oFileInfo))
+ bool gotFileInfo = m_oMS->FindFirst(m_acCurrentDirectory.c_str(), oFileInfo);
+ while (gotFileInfo && dirEntriesToSkip != 0)
{
- do
- {
- ++nDirReferencedLocation;
- }
- while ((nDirReferencedLocation < static_cast<int>(m_uListingFirstVisibleIndex - 1)) && m_oMS->FindNext(oFileInfo));
- // -- relying on short-circuit, do not change order!
+ --dirEntriesToSkip;
+ gotFileInfo = m_oMS->FindNext(oFileInfo);
}
- bool bAnotherFile = (-1 != nDirReferencedLocation);
-
-
- // i iterates over the visible lines on the screen (0, 1, 2...)
-
// We always iterate the entire viewport so that old listing lines that may not be overwritten are cleared
- for (/* uint8_t i = (0 == m_uListingFirstVisible ? 1 : 0) */ ; i < m_uDisplayLines; ++i, bAnotherFile = m_oMS->FindNext(oFileInfo))
+ while (line < numDisplayLines)
{
- lcd.SetCursor(row + (m_uFontHeight * i), column);
+ lcd.SetCursor(row + (lcd.GetFontHeight() * line), column);
// If there's actually a file to describe (not just ensuring viewport line clear)
- if (bAnotherFile)
+ if (gotFileInfo)
{
- if (highlight && (m_uListingSelectedIndex == (i + m_uListingFirstVisibleIndex)))
- lcd.print("> ");
- else
- lcd.print(" ");
-
+ lcd.print(" ");
if (oFileInfo.isDirectory)
+ {
lcd.print("./");
-
+ }
lcd.print(oFileInfo.fileName);
+ lcd.ClearToMargin();
+ if (highlight && m_uListingSelectedIndex == line + m_uListingFirstVisibleIndex)
+ {
+ lcd.SetCursor(row + (lcd.GetFontHeight() * line), column);
+ lcd.print(">");
+ }
}
-
- lcd.ClearToMargin();
- }
- }
- else // logical root, no ".." entry
- {
- // We are writing text to line numbers 0, 1 ... m_uDisplayLines - 1
- // These are fs entries m_uListingFirstVisibleIndex, m_uListingFirstVisibleIndex + 1 ... m_uListingFirstVisibleIndex + m_uDisplayLines - 1
-
- // Seek to the first file that is in view
- int nDirListingLocation = -1;
- FileInfo oFileInfo;
- if (m_oMS->FindFirst(m_acCurrentDirectory, oFileInfo))
- {
- do
+ else
{
- ++nDirListingLocation;
+ lcd.ClearToMargin();
}
- while ((nDirListingLocation < static_cast<int>(m_uListingFirstVisibleIndex)) && m_oMS->FindNext(oFileInfo));
- // -- relying on short-circuit, do not change order!
- }
-
- bool bAnotherFile = (-1 != nDirListingLocation);
- // We always iterate the entire viewport so that old listing lines that may not be overwritten are cleared
- for (uint8_t i = 0; i < m_uDisplayLines; ++i, bAnotherFile = m_oMS->FindNext(oFileInfo))
- {
- lcd.SetCursor(row + (m_uFontHeight * i), column);
-
- // If there's actually a file to describe (not just ensuring viewport line clear)
- if (bAnotherFile)
+ ++line;
+ if (line == numDisplayLines)
{
- if (highlight && (m_uListingSelectedIndex == (i + m_uListingFirstVisibleIndex)))
- lcd.print("> ");
- else
- lcd.print(" ");
-
- if (oFileInfo.isDirectory)
- lcd.print("./");
-
- lcd.print(oFileInfo.fileName);
+ break; // skip getting more file info for efficiency
}
-
- lcd.ClearToMargin();
+ gotFileInfo = m_oMS->FindNext(oFileInfo);
}
- }
- // TODO: cache these filenames to avoid the SD overhead each time...
+ m_oMS->AbandonFindNext(); // release the mutex, there may be more files that we don't have room to display
+
+ itemChanged = false;
+ highlighted = highlight;
+ }
}
void FilesMenuItem::Enter(bool bForwardDirection)
{
- if (bForwardDirection || 0 == uListingEntries())
+ if (bForwardDirection || uListingEntries() == 0)
{
m_uListingSelectedIndex = 0;
- m_uListingFirstVisibleIndex = 0;
+ m_uListingFirstVisibleIndex = 0; // select the first item and start the list form the first item
}
else
{
- m_uListingSelectedIndex = uListingEntries() - 1;
- m_uListingFirstVisibleIndex = ((uListingEntries() > m_uDisplayLines) ? (uListingEntries() - m_uDisplayLines) : 0);
+ m_uListingSelectedIndex = uListingEntries() - 1; // select the last item
+ m_uListingFirstVisibleIndex = ((uListingEntries() > numDisplayLines) ? (uListingEntries() - numDisplayLines) : 0);
}
+ itemChanged = true;
}
int FilesMenuItem::Advance(int nCounts)
{
// In case of empty directory, there's nothing the control itself can do
- if (0 == uListingEntries())
- {
- // Force the menu system to the next item in the list
- // ++nCounts;
- }
- else
+ if (uListingEntries() != 0)
{
while (nCounts > 0)
{
// Advancing one more would take us past the end of the list
- // Instead, return the remaining count so that the other
- // selectable menu items can be scrolled.
- if (uListingEntries() == m_uListingSelectedIndex + 1)
+ // Instead, return the remaining count so that the other selectable menu items can be scrolled.
+ if (m_uListingSelectedIndex + 1 == uListingEntries())
+ {
break;
+ }
++m_uListingSelectedIndex;
--nCounts;
// Move the visible portion of the list down, if required
- if (m_uListingSelectedIndex == m_uListingFirstVisibleIndex + m_uDisplayLines)
+ if (m_uListingSelectedIndex == m_uListingFirstVisibleIndex + numDisplayLines)
+ {
++m_uListingFirstVisibleIndex;
+ }
}
while (nCounts < 0)
{
- // We're already at the first item in the visible list;
- // return the remaining action to the menu system.
+ // We're already at the first item in the visible list; return the remaining action to the menu system.
if (0 == m_uListingSelectedIndex)
+ {
break;
+ }
--m_uListingSelectedIndex;
++nCounts;
// Move the visible portion of the list up, if required
if (m_uListingSelectedIndex < m_uListingFirstVisibleIndex)
+ {
--m_uListingFirstVisibleIndex;
+ }
}
+
+ itemChanged = true;
}
return nCounts;
@@ -720,7 +679,7 @@ int FilesMenuItem::Advance(int nCounts)
const char* FilesMenuItem::Select()
{
- char* acReVal = nullptr;
+ const char* acReVal = nullptr;
// Several cases:
// TEST 1. ".." entry - call EnterDirectory(), using saved state information
@@ -729,18 +688,17 @@ const char* FilesMenuItem::Select()
// Get information on the item selected
- if (bInSubdirectory() && (0 == m_uListingSelectedIndex)) // meaning ".."
+ if (bInSubdirectory() && 0 == m_uListingSelectedIndex) // meaning ".."
{
// TODO: go up one level rather than to logical root
// There's no guarantee that initialDirectory has a trailing '/'
- SafeStrncpy(m_acCurrentDirectory, initialDirectory, strlen(initialDirectory) + 1);
- // WS1 assumed safe
- if ('/' != m_acCurrentDirectory[strlen(m_acCurrentDirectory) - 1])
- SafeStrncpy(m_acCurrentDirectory + strlen(m_acCurrentDirectory), "/", 2);
- // WS1 assumed safe
-
+ m_acCurrentDirectory.copy(initialDirectory);
+ const size_t len = m_acCurrentDirectory.strlen();
+ if (len == 0 || '/' != m_acCurrentDirectory[len - 1])
+ {
+ m_acCurrentDirectory.cat('/');
+ }
EnterDirectory();
- // return nullptr;
}
else
{
@@ -749,73 +707,54 @@ const char* FilesMenuItem::Select()
// If ".." is not visible, the selected file is visible index m_uListingSelectedIndex, fs index m_uListingSelectedIndex - 1
// If logical root:
// ".." is never visible, so the selected file is visible index m_uListingSelectedIndex, fs index m_uListingSelectedIndex
-
- unsigned int uFindFileIndex = bInSubdirectory() ? m_uListingSelectedIndex - 1 : m_uListingSelectedIndex;
+ unsigned int dirEntriesToSkip = bInSubdirectory() ? m_uListingSelectedIndex - 1 : m_uListingSelectedIndex;
// Seek to the selected file
- int nDirectoryLocation = -1;
FileInfo oFileInfo;
- if (m_oMS->FindFirst(m_acCurrentDirectory, oFileInfo))
+ bool gotFileInfo = m_oMS->FindFirst(m_acCurrentDirectory.c_str(), oFileInfo);
+ while (gotFileInfo && dirEntriesToSkip != 0)
{
- do
- {
- ++nDirectoryLocation;
- }
- while ((nDirectoryLocation != static_cast<int>(uFindFileIndex)) && m_oMS->FindNext(oFileInfo)); // relying on short-circuit -- don't change order!
+ --dirEntriesToSkip;
+ gotFileInfo = m_oMS->FindNext(oFileInfo);
}
+ m_oMS->AbandonFindNext();
- if (nDirectoryLocation == static_cast<int>(uFindFileIndex)) // handles empty directory (no action)
+ if (gotFileInfo) // handles empty directory (no action)
{
if (oFileInfo.isDirectory)
{
// Build the new directory, and ensure it's terminated with a forward slash
- // TODO WS1
- SafeStrncpy(m_acCurrentDirectory + strlen(m_acCurrentDirectory), oFileInfo.fileName, min(strlen(oFileInfo.fileName) + 1, sizeof(m_acCurrentDirectory) - strlen(m_acCurrentDirectory)));
- SafeStrncpy(m_acCurrentDirectory + strlen(m_acCurrentDirectory), "/", min(2u, sizeof(m_acCurrentDirectory) - strlen(m_acCurrentDirectory)));
-
+ m_acCurrentDirectory.cat(oFileInfo.fileName);
+ m_acCurrentDirectory.cat('/');
EnterDirectory();
- // return nullptr;
}
else
{
- m_acCommand[0] = '\0';
-
- SafeStrncpy(m_acCommand, command, strlen(command) + 1);
- // WS1 assumed safe
-
- int nReplacementIndex = StringContains(m_acCommand, "#0");
- if (-1 != nReplacementIndex)
+ int nReplacementIndex = StringContains(command, "#0");
+ if (nReplacementIndex != -1)
{
- nReplacementIndex -= strlen("#0");
-
- SafeStrncpy(m_acCommand + nReplacementIndex, "\"", min(2u, sizeof(m_acCommand) - nReplacementIndex));
- ++nReplacementIndex;
-
- SafeStrncpy(m_acCommand + nReplacementIndex, m_acCurrentDirectory, min(strlen(m_acCurrentDirectory) + 1, sizeof(m_acCommand) - nReplacementIndex));
- nReplacementIndex += strlen(m_acCurrentDirectory);
-
- SafeStrncpy(m_acCommand + nReplacementIndex, oFileInfo.fileName, min(strlen(oFileInfo.fileName) + 1, sizeof(m_acCommand) - nReplacementIndex));
- nReplacementIndex += strlen(oFileInfo.fileName);
-
- SafeStrncpy(m_acCommand + nReplacementIndex, "\"", min(2u, sizeof(m_acCommand) - nReplacementIndex));
- ++nReplacementIndex;
-
- SafeStrncpy(m_acCommand + nReplacementIndex, command + StringContains(command, "#0"), min(strlen(command + StringContains(command, "#0")) + 1, sizeof(m_acCommand) - nReplacementIndex));
- // nReplacementIndex = ... // unused
+ m_acCommand.copy(command, nReplacementIndex);
+ m_acCommand.cat('"');
+ m_acCommand.cat(m_acCurrentDirectory.c_str());
+ m_acCommand.cat(oFileInfo.fileName);
+ m_acCommand.cat('"');
+ m_acCommand.cat(command + nReplacementIndex + strlen("#0"));
+ }
+ else
+ {
+ m_acCommand.copy(command);
}
// TODO: do this on the way in and it might be less work...
// On the other hand, this only occurs when an item is selected so it's O(1) vs. O(n)
- nReplacementIndex = StringContains(m_acCommand, "menu");
- if (-1 != nReplacementIndex)
+ nReplacementIndex = StringContains(m_acCommand.c_str(), "menu");
+ if (nReplacementIndex != -1)
{
- nReplacementIndex -= strlen("menu");
-
- SafeStrncpy(m_acCommand + nReplacementIndex, m_acFile, min(strlen(m_acFile) + 1, sizeof(m_acCommand) - nReplacementIndex));
+ m_acCommand.Truncate(nReplacementIndex);
+ m_acCommand.cat(m_acFile);
}
- acReVal = m_acCommand;
- // return m_acCommand; // would otherwise break encapsulation, but the return is const
+ acReVal = m_acCommand.c_str();
}
}
}
@@ -823,10 +762,70 @@ const char* FilesMenuItem::Select()
return acReVal;
}
-PixelNumber FilesMenuItem::GetVisibilityRowOffset(PixelNumber tCurrentOffset, const LcdFont *oFont) const
+PixelNumber FilesMenuItem::GetVisibilityRowOffset(PixelNumber tCurrentOffset, PixelNumber fontHeight) const
{
// TODO
return 0;
}
+// Image menu item members
+// The image file format is:
+// Byte 0 = number of columns
+// Byte 1 = number of rows
+// Remaining bytes = data, 1 row at a time. If the number of columns is not a multiple of 8 then the data for each row is padded to a multiple of 8 bits.
+ImageMenuItem::ImageMenuItem(PixelNumber r, PixelNumber c, const char *pFileName)
+ : MenuItem(r, c, 0)
+{
+ fileName.copy(pFileName);
+}
+
+void ImageMenuItem::Draw(Lcd7920& lcd, PixelNumber rightMargin, bool highlight, PixelNumber tOffset)
+{
+ // Highlighting is ignored for this item type because it can't be selected
+ if (itemChanged || highlight != highlighted)
+ {
+ FileStore * const fs = reprap.GetPlatform().OpenFile(MENU_DIR, fileName.c_str(), OpenMode::read);
+ if (fs != nullptr)
+ {
+ uint8_t widthAndHeight[2];
+ if (fs->Read(widthAndHeight, 2) == 2)
+ {
+ const PixelNumber cols = widthAndHeight[0];
+ const PixelNumber rows = widthAndHeight[1];
+ if (cols != 0 && cols <= NumCols && rows != 0)
+ {
+ lcd.SetRightMargin(rightMargin);
+ const size_t bytesPerRow = (cols + 7)/8;
+ for (PixelNumber irow = 0; irow < rows; ++irow)
+ {
+ uint8_t buffer[NumCols/8];
+ if (fs->Read(buffer, bytesPerRow) != (int)bytesPerRow)
+ {
+ break;
+ }
+ lcd.BitmapRow(row - tOffset + irow, column, cols, buffer, highlight);
+ ++irow;
+ }
+ }
+ }
+ fs->Close();
+ }
+ itemChanged = false;
+ highlighted = highlight;
+ }
+}
+
+PixelNumber ImageMenuItem::GetWidth() const
+{
+ FileStore * const fs = reprap.GetPlatform().OpenFile(MENU_DIR, fileName.c_str(), OpenMode::read);
+ if (fs == nullptr)
+ {
+ return 0;
+ }
+ uint8_t width;
+ fs->Read(width); // read the number of columns
+ fs->Close();
+ return width;
+}
+
// End
diff --git a/src/Display/MenuItem.h b/src/Display/MenuItem.h
index 02b25a4d..dae6238b 100644
--- a/src/Display/MenuItem.h
+++ b/src/Display/MenuItem.h
@@ -25,9 +25,9 @@ public:
virtual void Draw(Lcd7920& lcd, PixelNumber maxWidth, bool highlight, PixelNumber tOffset) = 0;
// Select this element with a push of the encoder.
- // If it returns nullptr then go into adjustment mode.
+ // If it returns nullptr then go into adjustment mode, if we can adjust the item.
// Else execute the returned command.
- virtual const char* Select() = 0;
+ virtual const char* Select() { return nullptr; }
virtual bool Visible() const { return true; }
@@ -41,15 +41,16 @@ public:
// Adjust this element, returning true if we have finished adjustment.
// 'clicks' is the number of encoder clicks to adjust by, or 0 if the button was pushed.
+ virtual bool CanAdjust() { return false; }
virtual bool Adjust(int clicks) { return true; }
- virtual bool CanAdjust() { return true; }
virtual ~MenuItem() { }
MenuItem *GetNext() const { return next; }
FontNumber GetFontNumber() const { return fontNumber; }
+ void SetChanged() { itemChanged = true; }
- virtual PixelNumber GetVisibilityRowOffset(PixelNumber tCurrentOffset, const LcdFont *oFont) const { return 0; }
+ virtual PixelNumber GetVisibilityRowOffset(PixelNumber tCurrentOffset, PixelNumber fontHeight) const { return 0; }
static void AppendToList(MenuItem **root, MenuItem *item);
@@ -59,6 +60,9 @@ protected:
const PixelNumber row, column;
const FontNumber fontNumber;
+ bool itemChanged;
+ bool highlighted;
+
private:
MenuItem *next;
};
@@ -74,13 +78,8 @@ public:
bool Visible() const override;
void Draw(Lcd7920& lcd, PixelNumber maxWidth, bool highlight, PixelNumber tOffset) override;
- const char* Select() override;
-
private:
- static TextMenuItem *freelist;
-
const char *text;
-
const Visibility m_xVisCase;
const CheckFunction m_bF;
};
@@ -96,11 +95,9 @@ public:
void Draw(Lcd7920& lcd, PixelNumber maxWidth, bool highlight, PixelNumber tOffset) override;
const char* Select() override;
- PixelNumber GetVisibilityRowOffset(PixelNumber tCurrentOffset, const LcdFont *oFont) const override;
+ PixelNumber GetVisibilityRowOffset(PixelNumber tCurrentOffset, PixelNumber fontHeight) const override;
private:
- static ButtonMenuItem *freelist;
-
const char *text;
const char *command;
const char *m_acFile; // used when action ("command") is "menu"
@@ -110,7 +107,7 @@ private:
// Scratch -- consumer is required to use as soon as it's returned
// NOT THREAD SAFE!
- char m_acCommand[MaxFilenameLength + 20]; // TODO fix to proper max length
+ String<MaxFilenameLength + 20> m_acCommand; // TODO fix to proper max length
};
class ValueMenuItem : public MenuItem
@@ -122,9 +119,10 @@ public:
ValueMenuItem(PixelNumber r, PixelNumber c, FontNumber fn, PixelNumber w, unsigned int v, unsigned int d);
void Draw(Lcd7920& lcd, PixelNumber maxWidth, bool highlight, PixelNumber tOffset) override;
const char* Select() override;
+ bool CanAdjust() override { return true; }
bool Adjust(int clicks) override;
- PixelNumber GetVisibilityRowOffset(PixelNumber tCurrentOffset, const LcdFont *oFont) const override;
+ PixelNumber GetVisibilityRowOffset(PixelNumber tCurrentOffset, PixelNumber fontHeight) const override;
unsigned int GetReferencedToolNumber() const;
@@ -145,14 +143,13 @@ public:
void* operator new(size_t sz) { return Allocate<FilesMenuItem>(); }
void operator delete(void* p) { Release<FilesMenuItem>(p); }
- FilesMenuItem(PixelNumber r, PixelNumber c, FontNumber fn, const char *cmd, const char *dir, const char *acFile, unsigned int nf, unsigned int uFontHeight);
+ FilesMenuItem(PixelNumber r, PixelNumber c, FontNumber fn, const char *cmd, const char *dir, const char *acFile, unsigned int nf);
void Draw(Lcd7920& lcd, PixelNumber rightMargin, bool highlight, PixelNumber tOffset) override;
void Enter(bool bForwardDirection) override;
int Advance(int nCounts) override;
const char* Select() override;
- bool CanAdjust() override { return false; }
- PixelNumber GetVisibilityRowOffset(PixelNumber tCurrentOffset, const LcdFont *oFont) const override;
+ PixelNumber GetVisibilityRowOffset(PixelNumber tCurrentOffset, PixelNumber fontHeight) const override;
void EnterDirectory();
@@ -160,24 +157,21 @@ protected:
void vResetViewState();
private:
- static FilesMenuItem *freelist;
+ const unsigned int numDisplayLines;
const char *command;
const char *initialDirectory;
const char *m_acFile; // used when action ("command") includes "menu"
- const unsigned int m_uDisplayLines;
- const unsigned int m_uFontHeight; // TODO: base has access to font number, is this necessary? API within other class may need to change to accommodate...
-
// Working
- char m_acCurrentDirectory[MaxFilenameLength];
+ String<MaxFilenameLength> m_acCurrentDirectory;
bool bInSubdirectory() const;
unsigned int uListingEntries() const;
// Scratch -- consumer is required to use as soon as it's returned
// NOT THREAD SAFE!
- char m_acCommand[MaxFilenameLength + 20]; // TODO fix to proper max length
+ String<MaxFilenameLength + 20> m_acCommand; // TODO fix to proper max length
// Files on the file system, real count i.e. no ".." included
unsigned int m_uHardItemsInDirectory;
@@ -189,4 +183,19 @@ private:
MassStorage *const m_oMS;
};
+class ImageMenuItem : public MenuItem
+{
+public:
+ void* operator new(size_t sz) { return Allocate<ImageMenuItem>(); }
+ void operator delete(void* p) { Release<ImageMenuItem>(p); }
+
+ ImageMenuItem(PixelNumber r, PixelNumber c, const char *pFileName);
+
+ void Draw(Lcd7920& lcd, PixelNumber rightMargin, bool highlight, PixelNumber tOffset) override;
+ PixelNumber GetWidth() const;
+
+private:
+ String<MaxFilenameLength> fileName;
+};
+
#endif /* SRC_DISPLAY_MENUITEM_H_ */
diff --git a/src/Display/RotaryEncoder.h b/src/Display/RotaryEncoder.h
index 972e7d93..097ff119 100644
--- a/src/Display/RotaryEncoder.h
+++ b/src/Display/RotaryEncoder.h
@@ -26,6 +26,7 @@ public:
void Poll();
int GetChange();
bool GetButtonPress();
+ int GetPulsesPerClick() const { return ppc; }
};
#endif
diff --git a/src/Display/ST7920/lcd7920.cpp b/src/Display/ST7920/lcd7920.cpp
index 9cd01d6a..054c9866 100644
--- a/src/Display/ST7920/lcd7920.cpp
+++ b/src/Display/ST7920/lcd7920.cpp
@@ -9,7 +9,7 @@
#include "lcd7920.h"
-const uint32_t SpiClockFrequency = 1600000; // 1.6MHz (minimum clock cycle time for ST7920 is 600ns @ Vdd=2.7V)
+const uint32_t SpiClockFrequency = 2000000; // 2.0MHz (minimum clock cycle time for ST7920 is 400ns @ Vdd=4.5V, min. clock width 200ns high and 20ns low)
// LCD basic instructions. These all take 72us to execute except LcdDisplayClear, which takes 1.6ms
const uint8_t LcdDisplayClear = 0x01;
@@ -26,12 +26,22 @@ const uint8_t LcdSetDdramAddress = 0x80; // add the address we want to set
// LCD extended instructions
const uint8_t LcdSetGdramAddress = 0x80;
-const unsigned int LcdCommandDelayMicros = 72 - 15; // 72us required, less 15us time to send the command @ 1MHz
+const unsigned int LcdCommandDelayMicros = 72 - 8; // 72us required, less 7us time to send the command @ 2.0MHz
const unsigned int LcdDataDelayMicros = 4; // delay between sending data bytes
const unsigned int LcdDisplayClearDelayMillis = 3; // 1.6ms should be enough
-Lcd7920::Lcd7920(uint8_t csPin)
- : currentFont(nullptr), numContinuationBytesLeft(0), textInverted(false)
+inline void Lcd7920::CommandDelay()
+{
+ delayMicroseconds(LcdCommandDelayMicros);
+}
+
+inline void Lcd7920::DataDelay()
+{
+ delayMicroseconds(LcdDataDelayMicros);
+}
+
+Lcd7920::Lcd7920(uint8_t csPin, const LcdFont * const fnts[], size_t nFonts)
+ : fonts(fnts), numFonts(nFonts), currentFontNumber(0), numContinuationBytesLeft(0), textInverted(false)
{
device.csPin = csPin;
device.csPolarity = true; // active high chip select
@@ -43,7 +53,9 @@ void Lcd7920::Init()
{
sspi_master_init(&device, 8);
numContinuationBytesLeft = 0;
- startRow = startCol = endRow = endCol = nextFlushRow = 0;
+ startRow = NumRows;
+ startCol = NumCols;
+ endRow = endCol = nextFlushRow = 0;
{
MutexLocker lock(Tasks::GetSpiMutex());
@@ -55,11 +67,11 @@ void Lcd7920::Init()
sendLcdCommand(LcdFunctionSetBasicAlpha);
delay(1);
sendLcdCommand(LcdFunctionSetBasicAlpha);
- commandDelay();
+ CommandDelay();
sendLcdCommand(LcdEntryModeSet);
- commandDelay();
+ CommandDelay();
sendLcdCommand(LcdFunctionSetExtendedGraphic);
- commandDelay();
+ CommandDelay();
sspi_deselect_device(&device);
}
@@ -74,15 +86,47 @@ void Lcd7920::Init()
sspi_select_device(&device);
delayMicroseconds(1);
sendLcdCommand(LcdDisplayOn);
- commandDelay();
+ CommandDelay();
sspi_deselect_device(&device);
}
- currentFont = nullptr;
+ currentFontNumber = 0;
+}
+
+void Lcd7920::SetFont(size_t newFont)
+{
+ if (newFont < numFonts)
+ {
+ currentFontNumber = newFont;
+ }
}
-void Lcd7920::SetFont(const LcdFont *newFont)
+// Get the current font height
+PixelNumber Lcd7920::GetFontHeight() const
{
- currentFont = newFont;
+ return fonts[currentFontNumber]->height;
+}
+
+// Get the height of a specified font
+PixelNumber Lcd7920::GetFontHeight(size_t fontNumber) const
+{
+ if (fontNumber >= numFonts)
+ {
+ fontNumber = currentFontNumber;
+ }
+ return fonts[fontNumber]->height;
+}
+
+// Flag a pixel as dirty. The r and c parameters must be no greater than NumRows-1 and NumCols-1 respectively.
+// Only one pixel in each 16-bit word needs to be flagged dirty for the whole word to get refreshed.
+void Lcd7920::SetDirty(PixelNumber r, PixelNumber c)
+{
+// if (r >= NumRows) { debugPrintf("r=%u\n", r); return; }
+// if (c >= NumCols) { debugPrintf("c=%u\n", c); return; }
+
+ if (c < startCol) { startCol = c; }
+ if (c >= endCol) { endCol = c + 1; }
+ if (r < startRow) { startRow = r; }
+ if (r >= endRow) { endRow = r + 1; }
}
// Write a UTF8 byte.
@@ -153,11 +197,7 @@ size_t Lcd7920::write(uint8_t c)
size_t Lcd7920::writeNative(uint16_t ch)
{
- if (currentFont == nullptr)
- {
- return 0;
- }
-
+ const LcdFont * const currentFont = fonts[currentFontNumber];
if (ch == '\n')
{
SetCursor(row + currentFont->height + 1, leftMargin);
@@ -176,7 +216,7 @@ size_t Lcd7920::writeNative(uint16_t ch)
const uint8_t bytesPerColumn = (ySize + 7)/8;
if (row >= NumRows)
{
- ySize = 0;
+ ySize = 0; // we still execute the code, so that the caller can tell how many columns the text will occupy by writing it off-screen
}
else if (row + ySize > NumRows)
{
@@ -189,15 +229,6 @@ size_t Lcd7920::writeNative(uint16_t ch)
uint8_t nCols = *fontPtr++;
- // Update dirty rectangle coordinates, except for endCol which we do at the end
- {
- if (startRow > row) { startRow = row; }
- if (startCol > column) { startCol = column; }
- uint8_t nextRow = row + ySize;
- if (nextRow > NumRows) { nextRow = NumRows; }
- if (endRow < nextRow) { endRow = nextRow; }
- }
-
if (lastCharColData != 0) // if we have written anything other than spaces
{
uint8_t numSpaces = currentFont->numSpaces;
@@ -227,13 +258,12 @@ size_t Lcd7920::writeNative(uint16_t ch)
uint8_t *p = image + ((row * (NumCols/8)) + (column/8));
for (uint8_t i = 0; i < ySize && p < (image + sizeof(image)); ++i)
{
- if (textInverted)
+ const uint8_t oldVal = *p;
+ const uint8_t newVal = (textInverted) ? oldVal | mask : oldVal & ~mask;
+ if (newVal != oldVal)
{
- *p |= mask;
- }
- else
- {
- *p &= ~mask;
+ *p = newVal;
+ SetDirty(row + i, column);
}
p += (NumCols/8);
}
@@ -250,31 +280,29 @@ size_t Lcd7920::writeNative(uint16_t ch)
{
lastCharColData = colData & cmask;
}
- const uint8_t mask1 = 0x80 >> (column & 7);
- const uint8_t mask2 = ~mask1;
- uint8_t *p = image + ((row * (NumCols/8)) + (column/8));
- const uint16_t setPixelVal = (textInverted) ? 0 : 1;
- for (uint8_t i = 0; i < ySize && p < (image + sizeof(image)); ++i)
+ if (ySize != 0)
{
- if ((colData & 1u) == setPixelVal)
- {
- *p |= mask1; // set pixel
- }
- else
+ const uint8_t mask1 = 0x80 >> (column & 7);
+ const uint8_t mask2 = ~mask1;
+ uint8_t *p = image + ((row * (NumCols/8)) + (column/8));
+ const uint16_t setPixelVal = (textInverted) ? 0 : 1;
+ for (uint8_t i = 0; i < ySize; ++i)
{
- *p &= mask2; // clear pixel
+ const uint8_t oldVal = *p;
+ const uint8_t newVal = ((colData & 1u) == setPixelVal) ? oldVal | mask1 : oldVal & mask2;
+ if (newVal != oldVal)
+ {
+ *p = newVal;
+ SetDirty(row + i, column);
+ }
+ colData >>= 1;
+ p += (NumCols/8);
}
- colData >>= 1;
- p += (NumCols/8);
}
--nCols;
++column;
}
- if (column > endCol)
- {
- endCol = min<uint8_t>(column, NumCols);
- }
justSetCursor = false;
}
return 1;
@@ -283,60 +311,46 @@ size_t Lcd7920::writeNative(uint16_t ch)
// Set the left margin. This is where the cursor goes to when we print newline.
void Lcd7920::SetLeftMargin(PixelNumber c)
{
- leftMargin = (c > NumCols) ? NumCols : c;
+ leftMargin = min<uint8_t>(c, NumCols);
}
// Set the right margin. In graphics mode, anything written will be truncated at the right margin. Defaults to the right hand edge of the display.
void Lcd7920::SetRightMargin(PixelNumber r)
{
- rightMargin = (r > NumCols) ? NumCols : r;
+ rightMargin = min<uint8_t>(r, NumCols);
}
// Clear a rectangle from the current position to the right margin. The height of the rectangle is the height of the current font.
void Lcd7920::ClearToMargin()
{
- if (currentFont != nullptr)
+ const uint8_t fontHeight = fonts[currentFontNumber]->height;
+ while (column < rightMargin)
{
- if (column < rightMargin)
+ uint8_t *p = image + ((row * (NumCols/8)) + (column/8));
+ uint8_t mask = 0xFF >> (column & 7);
+ PixelNumber nextColumn;
+ if ((column & (~7)) < (rightMargin & (~7)))
{
- const uint8_t fontHeight = currentFont->height;
- // Update dirty rectangle coordinates
- {
- if (startRow > row) { startRow = row; }
- if (startCol > column) { startCol = column; }
- uint8_t nextRow = row + fontHeight;
- if (nextRow > NumRows) { nextRow = NumRows; }
- if (endRow < nextRow) { endRow = nextRow; }
- if (endCol < rightMargin) { endCol = rightMargin; }
- }
+ nextColumn = (column & (~7)) + 8;
+ }
+ else
+ {
+ mask ^= 0xFF >> (rightMargin & 7);
+ nextColumn = rightMargin;;
+ }
- while (column < rightMargin)
+ for (uint8_t i = 0; i < fontHeight && p < (image + sizeof(image)); ++i)
+ {
+ const uint8_t oldVal = *p;
+ const uint8_t newVal = (textInverted) ? oldVal | mask : oldVal & ~mask;
+ if (newVal != oldVal)
{
- uint8_t *p = image + ((row * (NumCols/8)) + (column/8));
- uint8_t mask = 0xFF >> (column & 7);
- if ((column & (~7)) < (rightMargin & (~7)))
- {
- column = (column & (~7)) + 8;
- }
- else
- {
- mask ^= 0xFF >> (rightMargin & 7);
- column = rightMargin;;
- }
- for (uint8_t i = 0; i < fontHeight && p < (image + sizeof(image)); ++i)
- {
- if (textInverted)
- {
- *p |= mask;
- }
- else
- {
- *p &= ~mask;
- }
- p += (NumCols/8);
- }
+ *p = newVal;
+ SetDirty(row + i, column); // we refresh 16-bit words, so setting 1 pixel dirty in byte will suffice
}
+ p += (NumCols/8);
}
+ column = nextColumn;
}
}
@@ -352,36 +366,42 @@ void Lcd7920::TextInvert(bool b)
void Lcd7920::Clear(PixelNumber sRow, PixelNumber sCol, PixelNumber eRow, PixelNumber eCol)
{
- for (PixelNumber row = sRow; row < eRow; ++row)
+ if (eCol > NumCols) { eCol = NumCols; }
+ if (eRow > NumRows) { eRow = NumRows; }
+ if (sCol < eCol && sRow < eRow)
{
- PixelNumber col = sCol;
- if ((col & 7) != 0)
- {
- uint8_t * const p = image + ((row * (NumCols/8)) + (col/8));
- *p &= ~(0xFF >> (col & 7));
- col = (col & ~7) + 1;
- }
- while (col < eCol)
- {
- image[(row * (NumCols/8)) + (col/8)] = 0;
- col += 8;
- }
- if ((eCol & 7) != 0)
+ for (PixelNumber row = sRow; row < eRow; ++row)
{
- uint8_t * const p = image + ((row * (NumCols/8)) + (col/8));
- *p &= (0xFF >> (col & 7));
+ PixelNumber col = sCol;
+ if ((col & 7) != 0)
+ {
+ uint8_t * const p = image + ((row * (NumCols/8)) + (col/8));
+ *p &= ~(0xFF >> (col & 7));
+ col = (col & ~7) + 1;
+ }
+ while (col < eCol)
+ {
+ image[(row * (NumCols/8)) + (col/8)] = 0;
+ col += 8;
+ }
+ if ((eCol & 7) != 0)
+ {
+ uint8_t * const p = image + ((row * (NumCols/8)) + (col/8));
+ *p &= (0xFF >> (col & 7));
+ }
}
- }
- // Flag cleared part as dirty
- startRow = sRow;
- endRow = eRow;
- startCol = sCol;
- endCol = eCol;
- SetCursor(sRow, sCol);
- textInverted = false;
- leftMargin = sCol;
- rightMargin = eCol;
+ // Flag cleared part as dirty
+ startRow = sRow;
+ endRow = eRow;
+ startCol = sCol;
+ endCol = eCol;
+
+ SetCursor(sRow, sCol);
+ textInverted = false;
+ leftMargin = sCol;
+ rightMargin = eCol;
+ }
}
// Draw a line using the Bresenham Algorithm (thanks Wikipedia)
@@ -462,16 +482,62 @@ void Lcd7920::Bitmap(PixelNumber x0, PixelNumber y0, PixelNumber width, PixelNum
*p++ = data[bitMapOffset++];
}
}
+
+ // Assume the whole area has changed
if (x0 < startCol) startCol = x0;
if (x0 + width > endCol) endCol = x0 + width;
if (y0 < startRow) startRow = y0;
if (y0 + height > endRow) endRow = y0 + height;
}
-// Flush all of the dirty part of the image to the lcd
+// Draw a single bitmap row
+void Lcd7920::BitmapRow(PixelNumber top, PixelNumber left, PixelNumber width, const uint8_t data[], bool invert)
+{
+ if (width != 0) // avoid possible arithmetic underflow
+ {
+ const uint8_t inv = (invert) ? 0xFF : 0;
+ uint8_t firstColIndex = left/8; // column index of the first byte to write
+ const uint8_t lastColIndex = (left + width - 1)/8; // column index of the last byte to write
+ const unsigned int firstDataShift = left % 8; // number of bits in the first byte that we leave alone
+ uint8_t *p = image + (top * NumCols/8) + firstColIndex;
+
+ // Do all bytes except the last one
+ uint8_t accumulator = *p & (0xFF << (8 - firstDataShift)); // prime the accumulator
+ while (firstColIndex < lastColIndex)
+ {
+ const uint8_t invData = *data ^ inv;
+ const uint8_t newVal = accumulator | (invData >> firstDataShift);
+ if (newVal != *p)
+ {
+ *p = newVal;
+ SetDirty(top, 8 * firstColIndex);
+ }
+ accumulator = invData << (8 - firstDataShift);
+ ++p;
+ ++data;
+ ++firstColIndex;
+ }
+
+ // Do the last byte
+ const unsigned int lastDataShift = 7 - ((left + width - 1) % 8); // number of trailing bits in the last byte that we leave alone
+ const uint8_t lastMask = (1u << lastDataShift) - 1; // mask for bits we want to keep;
+ accumulator |= *p & lastMask;
+ const uint8_t newVal = accumulator | (((*data ^ inv) << (8 - firstDataShift)) & ~lastMask);
+ if (newVal != *p)
+ {
+ *p = newVal;
+ SetDirty(top, 8 * firstColIndex);
+ }
+ }
+}
+
+// Flush all of the dirty part of the image to the lcd. Only called during startup and shutdown.
void Lcd7920::FlushAll()
{
- while (FlushSome()) { }
+ while (FlushSome())
+ {
+ delayMicroseconds(20); // at 2MHz clock speed we need a delay here, at 1MHz we don't
+ }
}
// Flush some of the dirty part of the image to the LCD, returning true if there is more to do
@@ -483,32 +549,34 @@ bool Lcd7920::FlushSome()
// Decide which row to flush next
if (nextFlushRow < startRow || nextFlushRow >= endRow)
{
- nextFlushRow = startRow;
- ++startRow; // flag this row as flushed because it will be soon
+ nextFlushRow = startRow; // start from the beginning
+ }
+
+ if (nextFlushRow == startRow) // if we are starting form the beginning
+ {
+ ++startRow; // flag this row as flushed because it will be soon
}
// Flush that row
{
- const uint8_t startColNum = startCol/16;
+ uint8_t startColNum = startCol/16;
const uint8_t endColNum = (endCol + 15)/16;
+// debugPrintf("flush %u %u %u\n", nextFlushRow, startColNum, endColNum);
MutexLocker lock(Tasks::GetSpiMutex());
sspi_master_setup_device(&device);
- delayMicroseconds(1);
sspi_select_device(&device);
delayMicroseconds(1);
setGraphicsAddress(nextFlushRow, startColNum);
- uint8_t *ptr = image + ((16 * nextFlushRow) + (2 * startColNum));
- for (uint8_t i = startColNum; i < endColNum; ++i)
+ uint8_t *ptr = image + (((NumCols/8) * nextFlushRow) + (2 * startColNum));
+ while (startColNum < endColNum)
{
sendLcdData(*ptr++);
- //commandDelay(); // don't seem to need a delay here
sendLcdData(*ptr++);
- //commandDelay(); // don't seem to need as long a delay as this
- delayMicroseconds(LcdDataDelayMicros);
+ ++startColNum;
+ DataDelay();
}
-
sspi_deselect_device(&device);
}
@@ -540,24 +608,29 @@ void Lcd7920::SetPixel(PixelNumber y, PixelNumber x, PixelMode mode)
{
uint8_t * const p = image + ((y * (NumCols/8)) + (x/8));
const uint8_t mask = 0x80u >> (x%8);
+ const uint8_t oldVal = *p;
+ uint8_t newVal;
switch(mode)
{
case PixelMode::PixelClear:
- *p &= ~mask;
+ newVal = oldVal & ~mask;
break;
case PixelMode::PixelSet:
- *p |= mask;
+ newVal = oldVal | mask;
break;
case PixelMode::PixelFlip:
- *p ^= mask;
+ newVal = oldVal ^ mask;
+ break;
+ default:
+ newVal = oldVal;
break;
}
- // Change the dirty rectangle to account for a pixel being dirty (we assume it was changed)
- if (startRow > y) { startRow = y; }
- if (endRow <= y) { endRow = y + 1; }
- if (startCol > x) { startCol = x; }
- if (endCol <= x) { endCol = x + 1; }
+ if (newVal != oldVal)
+ {
+ *p = newVal;
+ SetDirty(y, x);
+ }
}
}
@@ -577,27 +650,23 @@ void Lcd7920::setGraphicsAddress(unsigned int r, unsigned int c)
sendLcdCommand(LcdSetGdramAddress | (r & 31));
//commandDelay(); // don't seem to need this one
sendLcdCommand(LcdSetGdramAddress | c | ((r & 32) >> 2));
- commandDelay(); // we definitely need this one
-}
-
-void Lcd7920::commandDelay()
-{
- delayMicroseconds(LcdCommandDelayMicros);
+ CommandDelay(); // we definitely need this one
}
-// Send a command to the LCD
+// Send a command to the LCD. The SPI mutex is already owned
void Lcd7920::sendLcdCommand(uint8_t command)
{
sendLcd(0xF8, command);
}
-// Send a data byte to the LCD
+// Send a data byte to the LCD. The SPI mutex is already owned
void Lcd7920::sendLcdData(uint8_t data)
{
sendLcd(0xFA, data);
}
// Send a command to the lcd. Data1 is sent as-is, data2 is split into 2 bytes, high nibble first.
+// The SPI mutex is already owned
void Lcd7920::sendLcd(uint8_t data1, uint8_t data2)
{
uint8_t data[3];
diff --git a/src/Display/ST7920/lcd7920.h b/src/Display/ST7920/lcd7920.h
index dfe656ce..fdfdbe40 100644
--- a/src/Display/ST7920/lcd7920.h
+++ b/src/Display/ST7920/lcd7920.h
@@ -35,10 +35,9 @@ class Lcd7920 : public Print
{
public:
// Construct a GLCD driver.
- Lcd7920(Pin csPin); // constructor
+ Lcd7920(Pin csPin, const LcdFont * const fnts[], size_t nFonts);
// Write a single character in the current font. Called by the 'print' functions.
- // A call to setFont must have been made before calling this.
// c = character to write
// Returns the number of characters written (1 if we wrote it, 0 otherwise)
virtual size_t write(uint8_t c); // write a character
@@ -46,12 +45,17 @@ public:
// Initialize the display. Call this in setup(). Also call setFont to select initial text font.
void Init();
- // Select the font to use for subsequent calls to write() in graphics mode. Must be called before calling write().
- // newFont = pointer to font descriptor in PROGMEM
- void SetFont(const LcdFont *newFont);
+ // Return the number of fonts
+ size_t GetNumFonts() const { return numFonts; }
+
+ // Select the font to use for subsequent calls to write() in graphics mode
+ void SetFont(size_t newFont);
// Get the current font height
- PixelNumber GetFontHeight() const { return currentFont->height; }
+ PixelNumber GetFontHeight() const;
+
+ // Get the height of a specified font
+ PixelNumber GetFontHeight(size_t fontNumber) const;
// Select normal or inverted text (only works in graphics mode)
void TextInvert(bool b);
@@ -62,7 +66,7 @@ public:
// Set the cursor position
// r = row, the number of pixels from the top of the display to the top of the character.
// c = column, is the number of pixels from the left hand edge of the display and the left hand edge of the character.
- void SetCursor(PixelNumber r, uint8_t c); // 'c' in alpha mode, should be an even column number
+ void SetCursor(PixelNumber r, PixelNumber c);
// Get the cursor row. Useful after we have written some text.
PixelNumber GetRow() const { return row; }
@@ -113,14 +117,23 @@ public:
// Draw a bitmap
// x0 = x-coordinate of the top left, measured from left hand edge of the display. Currently, must be a multiple of 8.
// y0 = y-coordinate of the top left, measured down from the top of the display
- // width = width of bitmap in pixels. Currently, must be a multiple of 8.
- // rows = height of bitmap in pixels
- // data = bitmap image in PROGMEM, must be ((width/8) * rows) bytes long
+ // width = width of bitmap in pixels. Currently, must be a multiple of 8.
+ // rows = height of bitmap in pixels
+ // data = bitmap image, must be ((width/8) * rows) bytes long
void Bitmap(PixelNumber top, PixelNumber left, PixelNumber height, PixelNumber width, const uint8_t data[]);
+ // Draw a bitmap row
+ // x0 = x-coordinate of the top left, measured from left hand edge of the display
+ // y0 = y-coordinate of the top left, measured down from the top of the display
+ // width = width of bitmap in pixels
+ // data = bitmap image, must be ((width + 7)/8) bytes long
+ void BitmapRow(PixelNumber top, PixelNumber left, PixelNumber width, const uint8_t data[], bool invert);
+
private:
+ const LcdFont * const *fonts;
+ const size_t numFonts;
+ size_t currentFontNumber; // index of the current font
uint32_t charVal;
- const LcdFont *currentFont; // pointer to descriptor for current font
sspi_device device;
uint16_t lastCharColData; // data for the last non-space column, used for kerning
uint8_t numContinuationBytesLeft;
@@ -135,10 +148,11 @@ private:
void sendLcdCommand(uint8_t command);
void sendLcdData(uint8_t data);
void sendLcd(uint8_t data1, uint8_t data2);
- void commandDelay();
+ void CommandDelay();
+ void DataDelay();
void setGraphicsAddress(unsigned int r, unsigned int c);
size_t writeNative(uint16_t c); // write a decoded character
-
+ void SetDirty(PixelNumber r, PixelNumber c);
};
#endif
diff --git a/src/Duet3/Pins_Duet3.h b/src/Duet3/Pins_Duet3.h
index 7fe5333d..12337323 100644
--- a/src/Duet3/Pins_Duet3.h
+++ b/src/Duet3/Pins_Duet3.h
@@ -14,15 +14,8 @@ const size_t NumFirmwareUpdateModules = 4; // 3 modules, plus one for manual up
#define HAS_CPU_TEMP_SENSOR 1
#define HAS_HIGH_SPEED_SD 1
-#define VARIANT_TMC5130 1
-
-#ifdef VARIANT_TMC5130
-# define SUPPORT_TMC51xx 1
-# define TMC51xx_USES_USART 1
-#else
-# define SUPPORT_TMC2660 1
-# define TMC2660_USES_USART 1
-#endif
+#define SUPPORT_TMC51xx 1
+#define TMC51xx_USES_USART 1
#define SUPPORT_CAN_EXPANSION 1
#define HAS_VOLTAGE_MONITOR 1
@@ -35,18 +28,14 @@ const size_t NumFirmwareUpdateModules = 4; // 3 modules, plus one for manual up
#define SUPPORT_IOBITS 1 // set to support P parameter in G0/G1 commands
#define SUPPORT_DHT_SENSOR 1 // set nonzero to support DHT temperature/humidity sensors
#define SUPPORT_WORKPLACE_COORDINATES 1 // set nonzero to support G10 L2 and G53..59
+#define SUPPORT_OBJECT_MODEL 1
#define USE_CACHE 0 // Cache controller disabled for now
// The physical capabilities of the machine
-#ifdef VARIANT_TMC5130
constexpr size_t NumDirectDrivers = 6; // The maximum number of drives supported by the electronics inc. direct expansion
constexpr size_t MaxSmartDrivers = 6; // The maximum number of smart drivers
-#else
-constexpr size_t NumDirectDrivers = 5; // The maximum number of drives supported by the electronics inc. direct expansion
-constexpr size_t MaxSmartDrivers = 5; // The maximum number of smart drivers
-#endif
constexpr size_t MaxCanDrivers = 12; // we need to set a limit until the DDA/DMs are restructured
constexpr size_t MaxTotalDrivers = NumDirectDrivers + MaxCanDrivers;
@@ -68,8 +57,6 @@ constexpr size_t NUM_SERIAL_CHANNELS = 2; // The number of serial IO channels
// DRIVES
-#ifdef VARIANT_TMC5130
-
constexpr Pin STEP_PINS[NumDirectDrivers] = { PORTC_PIN(18), PORTC_PIN(16), PORTC_PIN(28), PORTC_PIN(01), PORTC_PIN(04), PORTC_PIN(9) };
constexpr Pin DIRECTION_PINS[NumDirectDrivers] = { PORTB_PIN(05), PORTD_PIN(10), PORTA_PIN(04), PORTA_PIN(22), PORTC_PIN(03), PORTD_PIN(14) };
constexpr Pin DIAG_PINS[NumDirectDrivers] = { PORTD_PIN(19), PORTC_PIN(17), PORTD_PIN(13), PORTC_PIN(02), PORTD_PIN(31), PORTC_PIN(10) };
@@ -80,7 +67,7 @@ constexpr Pin GlobalTmc51xxCSPin = PORTD_PIN(17); // The pin that drives CS of
Usart * const USART_TMC51xx = USART1;
constexpr uint32_t ID_TMC51xx_SPI = ID_USART1;
constexpr IRQn TMC51xx_SPI_IRQn = USART1_IRQn;
-# define TMC51xx_SPI_Handler USART1_Handler
+#define TMC51xx_SPI_Handler USART1_Handler
// These next two are #defines to avoid the need to #include DmacManager.h here
#define TMC51xx_DmaTxPerid ((uint32_t)DmaTrigSource::usart1tx)
@@ -90,29 +77,6 @@ constexpr Pin TMC51xxMosiPin = PORTB_PIN(4);
constexpr Pin TMC51xxMisoPin = PORTA_PIN(21);
constexpr Pin TMC51xxSclkPin = PORTA_PIN(23);
-#else
-
-constexpr Pin ENABLE_PINS[DRIVES] = { NoPin, NoPin, NoPin, NoPin, NoPin };
-constexpr Pin STEP_PINS[DRIVES] = { NoPin, NoPin, NoPin, NoPin, NoPin };
-constexpr Pin DIRECTION_PINS[DRIVES] = { NoPin, NoPin, NoPin, NoPin, NoPin };
-
-// Pin assignments etc. using USART1 in SPI mode
-constexpr Pin GlobalTmc2660EnablePin = NoPin; // The pin that drives ENN of all TMC drivers
-Usart * const USART_TMC2660 = USART1;
-constexpr uint32_t ID_TMC2660_SPI = ID_USART1;
-constexpr IRQn TMC2660_SPI_IRQn = USART1_IRQn;
-# define TMC2660_SPI_Handler USART1_Handler
-
-// These next two are #defines to avoid the need to #include DmacManager.h here
-#define TMC2660_DmaTxPerid ((uint32_t)DmaTrigSource::usart1tx)
-#define TMC2660_DmaRxPerid ((uint32_t)DmaTrigSource::usart1rx)
-
-constexpr Pin TMC2660MosiPin = NoPin;
-constexpr Pin TMC2660MisoPin = NoPin;
-constexpr Pin TMC2660SclkPin = NoPin;
-
-#endif
-
constexpr size_t NumPwmOutputs = 11; // number of heater/fan/servo outputs
constexpr size_t NumInputOutputs = 9; // number of connectors we have for endstops, filament sensors, Z probes etc.
diff --git a/src/DuetM/Pins_DuetM.h b/src/DuetM/Pins_DuetM.h
index be5387a0..87ee327c 100644
--- a/src/DuetM/Pins_DuetM.h
+++ b/src/DuetM/Pins_DuetM.h
@@ -27,13 +27,14 @@ constexpr size_t NumFirmwareUpdateModules = 1; // 1 module
#define HAS_VREF_MONITOR 1
#define ACTIVE_LOW_HEAT_ON 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_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_INKJET 0 // set nonzero to support inkjet control
+#define SUPPORT_ROLAND 0 // set nonzero to support Roland mill
+#define SUPPORT_SCANNER 0 // set zero to disable support for FreeLSS scanners
+#define SUPPORT_IOBITS 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_12864_LCD 1 // set nonzero to support 12864 LCD and rotary encoder
+#define SUPPORT_OBJECT_MODEL 1
// The physical capabilities of the machine
diff --git a/src/DuetNG/Pins_DuetNG.h b/src/DuetNG/Pins_DuetNG.h
index 6f059479..d3381b9d 100644
--- a/src/DuetNG/Pins_DuetNG.h
+++ b/src/DuetNG/Pins_DuetNG.h
@@ -22,15 +22,16 @@ constexpr size_t NumFirmwareUpdateModules = 4; // 3 modules, plus one for manua
#define HAS_VREF_MONITOR 0
#define ACTIVE_LOW_HEAT_ON 1
-#define SUPPORT_INKJET 0 // set nonzero to support inkjet control
-#define SUPPORT_ROLAND 0 // set nonzero to support Roland mill
-#define SUPPORT_SCANNER 1 // set zero to disable support for FreeLSS scanners
-#define SUPPORT_LASER 1 // support laser cutters and engravers using G1 S parameter
-#define SUPPORT_IOBITS 1 // set to support P parameter in G0/G1 commands
-#define SUPPORT_DHT_SENSOR 1 // set nonzero to support DHT temperature/humidity sensors
+#define SUPPORT_INKJET 0 // set nonzero to support inkjet control
+#define SUPPORT_ROLAND 0 // set nonzero to support Roland mill
+#define SUPPORT_SCANNER 1 // set zero to disable support for FreeLSS scanners
+#define SUPPORT_LASER 1 // support laser cutters and engravers using G1 S parameter
+#define SUPPORT_IOBITS 1 // set to support P parameter in G0/G1 commands
+#define SUPPORT_DHT_SENSOR 1 // set nonzero to support DHT temperature/humidity sensors
#define SUPPORT_WORKPLACE_COORDINATES 1 // set nonzero to support G10 L2 and G53..59
+#define SUPPORT_OBJECT_MODEL 1
-#define USE_CACHE 0 // set nonzero to enable the cache. Disabled this at 1.21RC1 because of doubts about its safety.
+#define USE_CACHE 1 // set nonzero to enable the cache
// The physical capabilities of the machine
diff --git a/src/GCodes/GCodeBuffer.cpp b/src/GCodes/GCodeBuffer.cpp
index 607cd2cd..cf9443ed 100644
--- a/src/GCodes/GCodeBuffer.cpp
+++ b/src/GCodes/GCodeBuffer.cpp
@@ -418,6 +418,7 @@ FilePosition GCodeBuffer::GetFilePosition(size_t bytesCached) const
bool GCodeBuffer::Seen(char c)
{
bool inQuotes = false;
+ unsigned int inBrackets = 0;
for (readPointer = parameterStart; (unsigned int)readPointer < commandEnd; ++readPointer)
{
const char b = gcodeBuffer[readPointer];
@@ -425,9 +426,20 @@ bool GCodeBuffer::Seen(char c)
{
inQuotes = !inQuotes;
}
- else if (!inQuotes && toupper(b) == c)
+ else if (!inQuotes)
{
- return true;
+ if (inBrackets == 0 && toupper(b) == c)
+ {
+ return true;
+ }
+ if (b == '[')
+ {
+ ++inBrackets;
+ }
+ else if (b == ']' && inBrackets != 0)
+ {
+ --inBrackets;
+ }
}
}
readPointer = -1;
@@ -439,7 +451,7 @@ float GCodeBuffer::GetFValue()
{
if (readPointer >= 0)
{
- const float result = SafeStrtof(&gcodeBuffer[readPointer + 1], 0);
+ const float result = ReadFloatValue(&gcodeBuffer[readPointer + 1], nullptr);
readPointer = -1;
return result;
}
@@ -466,7 +478,7 @@ const void GCodeBuffer::GetFloatArray(float arr[], size_t& returnedLength, bool
return;
}
const char *q;
- arr[length] = SafeStrtof(p, &q);
+ arr[length] = ReadFloatValue(p, &q);
length++;
if (*q != LIST_SEPARATOR)
{
@@ -514,7 +526,7 @@ const void GCodeBuffer::GetIntArray(int32_t arr[], size_t& returnedLength, bool
return;
}
const char *q;
- arr[length] = SafeStrtol(p, &q);
+ arr[length] = ReadIValue(p, &q);
length++;
if (*q != LIST_SEPARATOR)
{
@@ -561,7 +573,7 @@ const void GCodeBuffer::GetUnsignedArray(uint32_t arr[], size_t& returnedLength,
return;
}
const char *q;
- arr[length] = SafeStrtoul(p, &q);
+ arr[length] = ReadUIValue(p, &q);
length++;
if (*q != LIST_SEPARATOR)
{
@@ -663,6 +675,10 @@ bool GCodeBuffer::InternalGetPossiblyQuotedString(const StringRef& str)
{
return InternalGetQuotedString(str);
}
+ if (gcodeBuffer[readPointer] == '[')
+ {
+ return GetStringExpression(str);
+ }
commandEnd = gcodeLineEnd; // the string is the remainder of the line of gcode
for (;;)
@@ -699,7 +715,7 @@ int32_t GCodeBuffer::GetIValue()
{
if (readPointer >= 0)
{
- const int32_t result = SafeStrtol(&gcodeBuffer[readPointer + 1]);
+ const int32_t result = ReadIValue(&gcodeBuffer[readPointer + 1], nullptr);
readPointer = -1;
return result;
}
@@ -839,7 +855,7 @@ bool GCodeBuffer::TryGetPossiblyQuotedString(char c, const StringRef& str, bool&
}
// Get an IP address quad after a key letter
-bool GCodeBuffer::GetIPAddress(uint8_t ip[4])
+bool GCodeBuffer::GetIPAddress(IPAddress& returnedIp)
{
if (readPointer < 0)
{
@@ -848,6 +864,7 @@ bool GCodeBuffer::GetIPAddress(uint8_t ip[4])
}
const char* p = &gcodeBuffer[readPointer + 1];
+ uint8_t ip[4];
unsigned int n = 0;
for (;;)
{
@@ -873,25 +890,13 @@ bool GCodeBuffer::GetIPAddress(uint8_t ip[4])
++p;
}
readPointer = -1;
- return n == 4;
-}
-
-// Get an IP address quad after a key letter
-bool GCodeBuffer::GetIPAddress(uint32_t& ip)
-{
- if (readPointer < 0)
+ if (n == 4)
{
- INTERNAL_ERROR;
- return false;
- }
-
- uint8_t ipa[4];
- const bool ok = GetIPAddress(ipa);
- if (ok)
- {
- ip = (uint32_t)ipa[0] | ((uint32_t)ipa[1] << 8) | ((uint32_t)ipa[2] << 16) | ((uint32_t)ipa[3] << 24);
+ returnedIp.SetV4(ip);
+ return true;
}
- return ok;
+ returnedIp.SetNull();
+ return false;
}
// Get a MAX address sextet after a key letter
@@ -1180,4 +1185,144 @@ void GCodeBuffer::FileEnded()
}
}
+// Functions to read values from lines of GCode, allowing for expressions and variable substitution
+float GCodeBuffer::ReadFloatValue(const char *p, const char **endptr)
+{
+#if SUPPORT_OBJECT_MODEL
+ if (*p == '[')
+ {
+ ExpressionValue val;
+ switch (EvaluateExpression(p, endptr, val))
+ {
+ case TYPE_OF(float):
+ return val.fVal;
+
+ case TYPE_OF(int32_t):
+ return (float)val.iVal;
+
+ case TYPE_OF(uint32_t):
+ return (float)val.uVal;
+
+ default:
+ //TODO report error
+ return 1.0;
+ }
+ }
+#endif
+
+ return SafeStrtof(p, endptr);
+}
+
+uint32_t GCodeBuffer::ReadUIValue(const char *p, const char **endptr)
+{
+#if SUPPORT_OBJECT_MODEL
+ if (*p == '[')
+ {
+ ExpressionValue val;
+ switch (EvaluateExpression(p, endptr, val))
+ {
+ case TYPE_OF(uint32_t):
+ return val.uVal;
+
+ case TYPE_OF(int32_t):
+ if (val.iVal >= 0)
+ {
+ return (uint32_t)val.iVal;
+ }
+ //TODO report error
+ return 0;
+
+ default:
+ //TODO report error
+ return 0;
+ }
+ }
+#endif
+
+ return SafeStrtoul(p, endptr);
+}
+
+int32_t GCodeBuffer::ReadIValue(const char *p, const char **endptr)
+{
+#if SUPPORT_OBJECT_MODEL
+ if (*p == '[')
+ {
+ ExpressionValue val;
+ switch (EvaluateExpression(p, endptr, val))
+ {
+ case TYPE_OF(int32_t):
+ return val.iVal;
+
+ case TYPE_OF(uint32_t):
+ return (int32_t)val.uVal;
+
+ default:
+ //TODO report error
+ return 0;
+ }
+ }
+#endif
+
+ return SafeStrtol(p, endptr);
+}
+
+// Get a string expression. The current character is '['.
+bool GCodeBuffer::GetStringExpression(const StringRef& str)
+{
+ ++readPointer;
+ for (;;)
+ {
+ const char c = gcodeBuffer[readPointer];
+ if (c == 0)
+ {
+ return false;
+ }
+ ++readPointer;
+ // For now we don't process the characters between { } and just return a standard string
+ if (c == ']')
+ {
+ str.copy("string_variables_not_implemented");
+ break;
+ }
+ }
+ return true;
+}
+
+#if SUPPORT_OBJECT_MODEL
+
+// Evaluate an expression. the current character is '['.
+TypeCode GCodeBuffer::EvaluateExpression(const char *p, const char **endptr, ExpressionValue& rslt)
+{
+ ++p; // skip the '['
+ // For now the only form of expression we handle is [variable-name]
+ if (isalpha(*p)) // if it's a variable name
+ {
+ const char * const start = p;
+ while (isalpha(*p) || isdigit(*p) || *p == '_')
+ {
+ ++p;
+ }
+ String<MaxVariableNameLength> varName;
+ if (varName.copy(start, p - start))
+ {
+ // variable name is too long
+ //TODO error handling
+ return NoType;
+ }
+ //TODO consider supporting standard CNC functions here
+ const TypeCode tc = reprap.GetObjectValue(rslt, varName.c_str());
+ if (tc != NoType && (tc & IsArray) == 0 && *p == ']')
+ {
+ if (endptr != nullptr)
+ {
+ *endptr = p + 1;
+ }
+ return tc;
+ }
+ }
+ return NoType;
+}
+
+#endif
+
// End
diff --git a/src/GCodes/GCodeBuffer.h b/src/GCodes/GCodeBuffer.h
index d82d9eaf..73227c6d 100644
--- a/src/GCodes/GCodeBuffer.h
+++ b/src/GCodes/GCodeBuffer.h
@@ -11,6 +11,7 @@
#include "RepRapFirmware.h"
#include "GCodeMachineState.h"
#include "MessageType.h"
+#include "ObjectModel/ObjectModel.h"
// Class to hold an individual GCode and provide functions to allow it to be parsed
class GCodeBuffer
@@ -34,8 +35,7 @@ public:
float GetFValue() __attribute__((hot)); // Get a float after a key letter
int32_t GetIValue() __attribute__((hot)); // Get an integer after a key letter
uint32_t GetUIValue(); // Get an unsigned integer value
- bool GetIPAddress(uint8_t ip[4]); // Get an IP address quad after a key letter
- bool GetIPAddress(uint32_t& ip); // Get an IP address quad after a key letter
+ bool GetIPAddress(IPAddress& returnedIp); // Get an IP address quad after a key letter
bool GetMacAddress(uint8_t mac[6]); // Get a MAX address sextet after a key letter
bool GetUnprecedentedString(const StringRef& str); // Get a string with no preceding key letter
bool GetQuotedString(const StringRef& str); // Get and copy a quoted string
@@ -116,9 +116,18 @@ private:
bool LineFinished(); // Deal with receiving end-of-line and return true if we have a command
void DecodeCommand();
bool InternalGetQuotedString(const StringRef& str)
- pre (gcodeBuffer[readPointer] == '"'; str.IsEmpty());
+ pre (readPointer >= 0; gcodeBuffer[readPointer] == '"'; str.IsEmpty());
bool InternalGetPossiblyQuotedString(const StringRef& str)
pre (readPointer >= 0);
+ float ReadFloatValue(const char *p, const char **endptr);
+ uint32_t ReadUIValue(const char *p, const char **endptr);
+ int32_t ReadIValue(const char *p, const char **endptr);
+ bool GetStringExpression(const StringRef& str)
+ pre (readPointer >= 0; gcodeBuffer[readPointer] == '{'; str.IsEmpty());
+
+#if SUPPORT_OBJECT_MODEL
+ TypeCode EvaluateExpression(const char *p, const char **endptr, ExpressionValue& rslt);
+#endif
GCodeMachineState *machineState; // Machine state for this gcode source
const char* const identity; // Where we are from (web, file, serial line etc)
diff --git a/src/GCodes/GCodeMachineState.h b/src/GCodes/GCodeMachineState.h
index 323ba860..40351fda 100644
--- a/src/GCodes/GCodeMachineState.h
+++ b/src/GCodes/GCodeMachineState.h
@@ -40,6 +40,9 @@ enum class GCodeState : uint8_t
pausing1,
pausing2,
+ filamentChangePause1,
+ filamentChangePause2,
+
resuming1,
resuming2,
resuming3,
diff --git a/src/GCodes/GCodeResult.h b/src/GCodes/GCodeResult.h
index 563029d7..45ea3af6 100644
--- a/src/GCodes/GCodeResult.h
+++ b/src/GCodes/GCodeResult.h
@@ -13,8 +13,8 @@
// Enumeration to specify the result of attempting to process a GCode command
enum class GCodeResult : uint8_t
{
- notFinished,
- ok,
+ notFinished, // we havebn't finished processing this command
+ ok, // we have finished processing this code in the current state, and if the GCodeState is 'normal' then we have finished it completely
error,
warning,
notSupported,
diff --git a/src/GCodes/GCodes.cpp b/src/GCodes/GCodes.cpp
index 15d99465..18955f15 100644
--- a/src/GCodes/GCodes.cpp
+++ b/src/GCodes/GCodes.cpp
@@ -59,30 +59,21 @@ void GCodes::RawMove::SetDefaults()
yAxes = DefaultYAxisMapping;
}
-#ifdef SUPPORT_OBJECT_MODEL
+#if SUPPORT_OBJECT_MODEL
// Object model table and functions
-// Note: if using GCC version 7.3.1 20180622 then if lambda functions are used in this table, you must compile this file with option -std=gnu++17.
-// Otherwise the table will be allocate in RAM instead of flash, which wastes too much RAM.
+// Note: if using GCC version 7.3.1 20180622 and lambda functions are used in this table, you must compile this file with option -std=gnu++17.
+// Otherwise the table will be allocated in RAM instead of flash, which wastes too much RAM.
// Macro to build a standard lambda function that includes the necessary type conversions
-#define OBJECT_MODEL_FUNC(_ret) [] (ObjectModel* arg) { GCodes * const self = static_cast<GCodes*>(arg); return (void *)(_ret); }
+#define OBJECT_MODEL_FUNC(_ret) OBJECT_MODEL_FUNC_BODY(GCodes, _ret)
const ObjectModelTableEntry GCodes::objectModelTable[] =
{
{ "speedFactor", OBJECT_MODEL_FUNC(&(self->speedFactor)), TYPE_OF(float), ObjectModelTableEntry::none }
};
-const char *GCodes::GetModuleName() const
-{
- return nullptr; // this module has no name and doesn't need one
-}
-
-const ObjectModelTableEntry *GCodes::GetObjectModelTable(size_t& numEntries) const
-{
- numEntries = ARRAY_SIZE(objectModelTable);
- return objectModelTable;
-}
+DEFINE_GET_OBJECT_MODEL_TABLE(GCodes)
#endif
@@ -94,21 +85,19 @@ GCodes::GCodes(Platform& p) :
isFlashing(false), fileBeingHashed(nullptr), lastWarningMillis(0)
{
fileInput = new FileGCodeInput();
+ fileGCode = new GCodeBuffer("file", GenericMessage, true);
serialInput = new StreamGCodeInput(SERIAL_MAIN_DEVICE);
-#ifdef SERIAL_AUX_DEVICE
- auxInput = new StreamGCodeInput(SERIAL_AUX_DEVICE);
-#endif
+ serialGCode = new GCodeBuffer("serial", UsbMessage, true);
#if HAS_NETWORKING
httpInput = new NetworkGCodeInput;
- telnetInput = new NetworkGCodeInput;
httpGCode = new GCodeBuffer("http", HttpMessage, false);
+ telnetInput = new NetworkGCodeInput;
telnetGCode = new GCodeBuffer("telnet", TelnetMessage, true);
#else
httpGCode = telnetGCode = nullptr;
#endif
- fileGCode = new GCodeBuffer("file", GenericMessage, true);
- serialGCode = new GCodeBuffer("serial", UsbMessage, true);
#ifdef SERIAL_AUX_DEVICE
+ auxInput = new StreamGCodeInput(SERIAL_AUX_DEVICE);
auxGCode = new GCodeBuffer("aux", LcdMessage, false);
#else
auxGCode = nullptr;
@@ -528,9 +517,9 @@ void GCodes::RunStateMachine(GCodeBuffer& gb, const StringRef& reply)
}
else
{
- AxesBitmap mustHomeFirst;
- const char *nextHomingFile = reprap.GetMove().GetKinematics().GetHomingFileName(toBeHomed, axesHomed, numVisibleAxes, mustHomeFirst);
- if (nextHomingFile == nullptr)
+ String<PASSWORD_LENGTH> nextHomingFileName;
+ AxesBitmap mustHomeFirst = reprap.GetMove().GetKinematics().GetHomingFileName(toBeHomed, axesHomed, numVisibleAxes, nextHomingFileName.GetRef());
+ if (mustHomeFirst != 0)
{
// Error, can't home this axes
reply.copy("Must home these axes:");
@@ -544,9 +533,9 @@ void GCodes::RunStateMachine(GCodeBuffer& gb, const StringRef& reply)
else
{
gb.SetState(GCodeState::homing2);
- if (!DoFileMacro(gb, nextHomingFile, false))
+ if (!DoFileMacro(gb, nextHomingFileName.c_str(), false))
{
- reply.printf("Homing file %s not found", nextHomingFile);
+ reply.printf("Homing file %s not found", nextHomingFileName.c_str());
error = true;
gb.SetState(GCodeState::normal);
}
@@ -653,7 +642,7 @@ void GCodes::RunStateMachine(GCodeBuffer& gb, const StringRef& reply)
break;
case GCodeState::m109WaitForTemperature:
- if (cancelWait || simulationMode != 0 || ToolHeatersAtSetTemperatures(reprap.GetCurrentTool(), gb.MachineState().waitWhileCooling))
+ if (cancelWait || simulationMode != 0 || ToolHeatersAtSetTemperatures(reprap.GetCurrentTool(), gb.MachineState().waitWhileCooling, TEMPERATURE_CLOSE_ENOUGH))
{
cancelWait = isWaiting = false;
gb.SetState(GCodeState::normal);
@@ -668,7 +657,7 @@ void GCodes::RunStateMachine(GCodeBuffer& gb, const StringRef& reply)
case GCodeState::pausing1:
if (LockMovementAndWaitForStandstill(gb))
{
- gb.SetState(GCodeState::pausing2);
+ gb.AdvanceState();
if (AllAxesAreHomed())
{
DoFileMacro(gb, PAUSE_G, true);
@@ -676,10 +665,25 @@ void GCodes::RunStateMachine(GCodeBuffer& gb, const StringRef& reply)
}
break;
+ case GCodeState::filamentChangePause1:
+ if (LockMovementAndWaitForStandstill(gb))
+ {
+ gb.AdvanceState();
+ if (AllAxesAreHomed())
+ {
+ if (!DoFileMacro(gb, FILAMENT_CHANGE_G, false))
+ {
+ DoFileMacro(gb, PAUSE_G, true);
+ }
+ }
+ }
+ break;
+
case GCodeState::pausing2:
+ case GCodeState::filamentChangePause2:
if (LockMovementAndWaitForStandstill(gb))
{
- reply.printf("Printing paused at");
+ reply.printf((gb.GetState() == GCodeState::filamentChangePause2) ? "Printing paused for filament change at" : "Printing paused at");
for (size_t axis = 0; axis < numVisibleAxes; ++axis)
{
reply.catf(" %c%.1f", axisLetters[axis], (double)pauseRestorePoint.moveCoords[axis]);
@@ -954,11 +958,29 @@ void GCodes::RunStateMachine(GCodeBuffer& gb, const StringRef& reply)
{
// See whether we need to do any more taps
const ZProbe& params = platform.GetCurrentZProbeParameters();
- if (tapsDone >= 2)
+ bool acceptReading = false;
+ if (params.maxTaps < 2)
+ {
+ acceptReading = true;
+ }
+ else if (tapsDone >= 2)
{
g30zHeightErrorLowestDiff = min<float>(g30zHeightErrorLowestDiff, fabsf(g30zHeightError - g30PrevHeightError));
+ if (params.tolerance > 0.0)
+ {
+ if (g30zHeightErrorLowestDiff <= params.tolerance)
+ {
+ g30zHeightError = (g30zHeightError + g30PrevHeightError)/2;
+ acceptReading = true;
+ }
+ }
+ else if (tapsDone == params.maxTaps)
+ {
+ g30zHeightError = g30zHeightErrorSum/tapsDone;
+ acceptReading = true;
+ }
}
- const bool acceptReading = (params.maxTaps < 2 || (tapsDone >= 2 && g30zHeightErrorLowestDiff <= params.tolerance));
+
if (acceptReading)
{
reprap.GetMove().AccessHeightMap().SetGridHeight(gridXindex, gridYindex, g30zHeightError);
@@ -1044,6 +1066,10 @@ void GCodes::RunStateMachine(GCodeBuffer& gb, const StringRef& reply)
error = true;
}
}
+ if (!error)
+ {
+ reprap.GetPlatform().MessageF(LogMessage, "%s\n", reply.c_str());
+ }
gb.SetState(GCodeState::normal);
break;
@@ -1157,7 +1183,7 @@ void GCodes::RunStateMachine(GCodeBuffer& gb, const StringRef& reply)
if (platform.GetZProbeType() == ZProbeType::none)
{
// No Z probe, so we are doing manual mesh levelling. Take the current Z height as the height error.
- g30zHeightError = moveBuffer.coords[Z_AXIS];
+ g30zStoppedHeight = g30zHeightError = moveBuffer.coords[Z_AXIS];
}
else
{
@@ -1230,51 +1256,56 @@ void GCodes::RunStateMachine(GCodeBuffer& gb, const StringRef& reply)
{
// See whether we need to do any more taps
const ZProbe& params = platform.GetCurrentZProbeParameters();
- if (tapsDone >= 2)
+ bool acceptReading = false;
+ if (params.maxTaps < 2)
{
- g30zHeightErrorLowestDiff = min<float>(g30zHeightErrorLowestDiff, fabsf(g30zHeightError - g30PrevHeightError));
+ acceptReading = true;
}
- const bool acceptReading = (hadProbingError || params.maxTaps < 2 || (tapsDone >= 2 && g30zHeightErrorLowestDiff <= params.tolerance));
- if (!acceptReading && tapsDone < params.maxTaps)
+ else if (tapsDone >= 2)
{
- // Tap again
- g30PrevHeightError = g30zHeightError;
- lastProbedTime = millis();
- gb.SetState(GCodeState::probingAtPoint2a);
+ g30zHeightErrorLowestDiff = min<float>(g30zHeightErrorLowestDiff, fabsf(g30zHeightError - g30PrevHeightError));
+ if (params.tolerance > 0.0 && g30zHeightErrorLowestDiff <= params.tolerance)
+ {
+ g30zHeightError = (g30zHeightError + g30PrevHeightError)/2;
+ acceptReading = true;
+ }
}
- else
+
+ if (!acceptReading)
{
- if (acceptReading)
+ if (tapsDone < params.maxTaps)
{
- if (tapsDone >= 2)
- {
- g30zHeightError = (g30zHeightError + g30PrevHeightError)/2; // take the average of the two readings
- }
+ // Tap again
+ g30PrevHeightError = g30zHeightError;
+ lastProbedTime = millis();
+ gb.SetState(GCodeState::probingAtPoint2a);
+ break;
}
- else
+
+ // We no longer flag this as a probing error, instead we take the average and issue a warning
+ g30zHeightError = g30zHeightErrorSum/tapsDone;
+ if (params.tolerance > 0.0) // zero or negative tolerance means always average all readings
{
- // We no longer flag this as a probing error, instead we take the average and issue a warning
platform.Message(WarningMessage, "Z probe readings not consistent\n");
- g30zHeightError = g30zHeightErrorSum/tapsDone;
}
+ }
- if (g30ProbePointIndex >= 0)
- {
- reprap.GetMove().SetZBedProbePoint(g30ProbePointIndex, g30zHeightError, true, hadProbingError);
- }
- else
- {
- // Setting the Z height with G30
- moveBuffer.coords[Z_AXIS] -= g30zHeightError;
- reprap.GetMove().SetNewPosition(moveBuffer.coords, false);
- reprap.GetMove().SetZeroHeightError(moveBuffer.coords);
- ToolOffsetInverseTransform(moveBuffer.coords, currentUserPosition);
- }
- gb.AdvanceState();
- if (platform.GetZProbeType() != ZProbeType::none && !probeIsDeployed)
- {
- DoFileMacro(gb, RETRACTPROBE_G, false);
- }
+ if (g30ProbePointIndex >= 0)
+ {
+ reprap.GetMove().SetZBedProbePoint(g30ProbePointIndex, g30zHeightError, true, hadProbingError);
+ }
+ else
+ {
+ // Setting the Z height with G30
+ moveBuffer.coords[Z_AXIS] -= g30zHeightError;
+ reprap.GetMove().SetNewPosition(moveBuffer.coords, false);
+ reprap.GetMove().SetZeroHeightError(moveBuffer.coords);
+ ToolOffsetInverseTransform(moveBuffer.coords, currentUserPosition);
+ }
+ gb.AdvanceState();
+ if (platform.GetZProbeType() != ZProbeType::none && !probeIsDeployed)
+ {
+ DoFileMacro(gb, RETRACTPROBE_G, false);
}
}
break;
@@ -1754,7 +1785,7 @@ void GCodes::DoPause(GCodeBuffer& gb, PauseReason reason, const char *msg)
SaveResumeInfo(false); // create the resume file so that we can resume after power down
}
- gb.SetState(GCodeState::pausing1);
+ gb.SetState((reason == PauseReason::filamentChange) ? GCodeState::filamentChangePause1 : GCodeState::pausing1);
isPaused = true;
if (msg != nullptr)
@@ -2624,9 +2655,9 @@ const char* GCodes::DoArcMove(GCodeBuffer& gb, bool clockwise)
jParam = 0.0;
}
- if (!seenXY && seenIJ) // at least one of XY and IJ must be specified
+ if (!(seenXY && seenIJ)) // at least one of XY and IJ must be specified
{
- return "G2/G3: missing parameter";
+ return "G2/G3: missing parameter";
}
memcpy(moveBuffer.initialCoords, moveBuffer.coords, numVisibleAxes * sizeof(moveBuffer.initialCoords[0]));
@@ -3704,8 +3735,8 @@ void GCodes::HandleReply(GCodeBuffer& gb, GCodeResult rslt, const char* reply)
case Compatibility::me:
case Compatibility::reprapFirmware:
{
- const MessageType mt = (rslt == GCodeResult::error) ? (MessageType)(type | ErrorMessageFlag)
- : (rslt == GCodeResult::warning) ? (MessageType)(type | WarningMessageFlag)
+ const MessageType mt = (rslt == GCodeResult::error) ? (MessageType)(type | ErrorMessageFlag | LogMessage)
+ : (rslt == GCodeResult::warning) ? (MessageType)(type | WarningMessageFlag | LogMessage)
: type;
platform.MessageF(mt, "%s\n", reply);
}
@@ -3754,7 +3785,8 @@ void GCodes::HandleReply(GCodeBuffer& gb, GCodeResult rslt, const char* reply)
}
}
-void GCodes::HandleReply(GCodeBuffer& gb, bool error, OutputBuffer *reply)
+// Handle a successful response when the response is in an OutputBuffer
+void GCodes::HandleReply(GCodeBuffer& gb, OutputBuffer *reply)
{
// Although unlikely, it's possible that we get a nullptr reply. Don't proceed if this is the case
if (reply == nullptr)
@@ -3778,10 +3810,6 @@ void GCodes::HandleReply(GCodeBuffer& gb, bool error, OutputBuffer *reply)
{
case Compatibility::me:
case Compatibility::reprapFirmware:
- if (error)
- {
- platform.Message(type, "Error: ");
- }
platform.Message(type, reply);
return;
@@ -4373,13 +4401,13 @@ void GCodes::StopPrint(StopPrintReason reason)
}
// Return true if all the heaters for the specified tool are at their set temperatures
-bool GCodes::ToolHeatersAtSetTemperatures(const Tool *tool, bool waitWhenCooling) const
+bool GCodes::ToolHeatersAtSetTemperatures(const Tool *tool, bool waitWhenCooling, float tolerance) const
{
if (tool != nullptr)
{
for (size_t i = 0; i < tool->HeaterCount(); ++i)
{
- if (!reprap.GetHeat().HeaterAtSetTemperature(tool->Heater(i), waitWhenCooling))
+ if (!reprap.GetHeat().HeaterAtSetTemperature(tool->Heater(i), waitWhenCooling, tolerance))
{
return false;
}
@@ -4516,7 +4544,7 @@ void GCodes::ToolOffsetInverseTransform(const float coordsIn[MaxAxes], float coo
axisOffsets[axis]
#endif
- currentTool->GetOffset(axis);
- coordsOut[axis] = coordsIn[axis] + currentTool->GetOffset(axis);
+ coordsOut[axis] = coordsIn[axis]/axisScaleFactors[axis] - totalOffset;
if (IsBitSet(xAxes, axis))
{
xCoord += coordsIn[axis]/axisScaleFactors[axis] - totalOffset;
diff --git a/src/GCodes/GCodes.h b/src/GCodes/GCodes.h
index 97624610..b8618b5f 100644
--- a/src/GCodes/GCodes.h
+++ b/src/GCodes/GCodes.h
@@ -82,6 +82,7 @@ enum class PauseReason
{
user, // M25 command received
gcode, // M25 or M226 command encountered in the file being printed
+ filamentChange, // M600 command
trigger, // external switch
heaterFault, // heater fault detected
filament, // filament monitor
@@ -104,10 +105,7 @@ enum class StopPrintReason
// The GCode interpreter
-class GCodes
-#ifdef SUPPORT_OBJECT_MODEL
- : public ObjectModel
-#endif
+class GCodes INHERIT_OBJECT_MODEL
{
public:
struct RawMove
@@ -229,13 +227,8 @@ public:
void HandleReply(GCodeBuffer& gb, GCodeResult rslt, const char *reply); // Handle G-Code replies
void EmergencyStop(); // Cancel everything
-#ifdef SUPPORT_OBJECT_MODEL
protected:
- const char *GetModuleName() const override;
- const ObjectModelTableEntry *GetObjectModelTable(size_t& numEntries) const override;
-
- static const ObjectModelTableEntry objectModelTable[];
-#endif
+ DECLARE_OBJECT_MODEL
private:
GCodes(const GCodes&); // private copy constructor to prevent copying
@@ -274,8 +267,10 @@ private:
bool HandleGcode(GCodeBuffer& gb, const StringRef& reply); // Do a G code
bool HandleMcode(GCodeBuffer& gb, const StringRef& reply); // Do an M code
bool HandleTcode(GCodeBuffer& gb, const StringRef& reply); // Do a T code
- bool HandleResult(GCodeBuffer& gb, GCodeResult rslt, const StringRef& reply);
- void HandleReply(GCodeBuffer& gb, bool error, OutputBuffer *reply);
+ bool HandleResult(GCodeBuffer& gb, GCodeResult rslt, const StringRef& reply, OutputBuffer *outBuf)
+ pre(outBuf == nullptr || rslt == GCodeResult::ok);
+
+ void HandleReply(GCodeBuffer& gb, OutputBuffer *reply);
const char* DoStraightMove(GCodeBuffer& gb, bool isCoordinated) __attribute__((hot)); // Execute a straight move returning any error message
const char* DoArcMove(GCodeBuffer& gb, bool clockwise) // Execute an arc move returning any error message
@@ -318,7 +313,8 @@ private:
GCodeResult SetHeaterParameters(GCodeBuffer& gb, const StringRef& reply); // Set the thermistor and ADC parameters for a heater, returning true if an error occurs
bool ManageTool(GCodeBuffer& gb, const StringRef& reply); // Create a new tool definition, returning true if an error was reported
void SetToolHeaters(Tool *tool, float temperature, bool both); // Set all a tool's heaters to the temperature, for M104/M109
- bool ToolHeatersAtSetTemperatures(const Tool *tool, bool waitWhenCooling) const; // Wait for the heaters associated with the specified tool to reach their set temperatures
+ bool ToolHeatersAtSetTemperatures(const Tool *tool, bool waitWhenCooling, float tolerance) const;
+ // Wait for the heaters associated with the specified tool to reach their set temperatures
void ReportToolTemperatures(const StringRef& reply, const Tool *tool, bool includeNumber) const;
void GenerateTemperatureReport(const StringRef& reply) const; // Store a standard-format temperature report in reply
OutputBuffer *GenerateJsonStatusResponse(int type, int seq, ResponseSource source) const; // Generate a M408 response
@@ -589,6 +585,7 @@ private:
static constexpr const char* UNLOAD_FILAMENT_G = "unload.g";
static constexpr const char* RESUME_AFTER_POWER_FAIL_G = "resurrect.g";
static constexpr const char* RESUME_PROLOGUE_G = "resurrect-prologue.g";
+ static constexpr const char* FILAMENT_CHANGE_G = "filament-change.g";
#if HAS_SMART_DRIVERS
static constexpr const char* REHOME_G = "rehome.g";
#endif
diff --git a/src/GCodes/GCodes2.cpp b/src/GCodes/GCodes2.cpp
index fa4e45c5..578b1d48 100644
--- a/src/GCodes/GCodes2.cpp
+++ b/src/GCodes/GCodes2.cpp
@@ -338,12 +338,13 @@ bool GCodes::HandleGcode(GCodeBuffer& gb, const StringRef& reply)
result = GCodeResult::notSupported;
}
- return HandleResult(gb, result, reply);
+ return HandleResult(gb, result, reply, nullptr);
}
bool GCodes::HandleMcode(GCodeBuffer& gb, const StringRef& reply)
{
GCodeResult result = GCodeResult::ok;
+ OutputBuffer *outBuf = nullptr;
const int code = gb.GetCommandNumber();
if ( simulationMode != 0
@@ -580,28 +581,27 @@ bool GCodes::HandleMcode(GCodeBuffer& gb, const StringRef& reply)
dir.copy(platform.GetGCodeDir());
}
- OutputBuffer *fileResponse;
if (sparam == 2)
{
- fileResponse = reprap.GetFilesResponse(dir.c_str(), rparam, true); // send the file list in JSON format
- if (fileResponse == nullptr)
+ outBuf = reprap.GetFilesResponse(dir.c_str(), rparam, true); // send the file list in JSON format
+ if (outBuf == nullptr)
{
return false;
}
- fileResponse->cat('\n');
+ outBuf->cat('\n');
}
else if (sparam == 3)
{
- fileResponse = reprap.GetFilelistResponse(dir.c_str(), rparam);
- if (fileResponse == nullptr)
+ outBuf = reprap.GetFilelistResponse(dir.c_str(), rparam);
+ if (outBuf == nullptr)
{
return false;
}
- fileResponse->cat('\n');
+ outBuf->cat('\n');
}
else
{
- if (!OutputBuffer::Allocate(fileResponse))
+ if (!OutputBuffer::Allocate(outBuf))
{
return false; // cannot allocate an output buffer, try again later
}
@@ -612,7 +612,7 @@ bool GCodes::HandleMcode(GCodeBuffer& gb, const StringRef& reply)
// otherwise we put quotes around them and separate them with comma.
if (platform.Emulating() == Compatibility::me || platform.Emulating() == Compatibility::reprapFirmware)
{
- fileResponse->copy("GCode files:\n");
+ outBuf->copy("GCode files:\n");
}
bool encapsulateList = ((&gb != serialGCode && &gb != telnetGCode) || platform.Emulating() != Compatibility::marlin);
@@ -623,30 +623,27 @@ bool GCodes::HandleMcode(GCodeBuffer& gb, const StringRef& reply)
do {
if (encapsulateList)
{
- fileResponse->catf("%c%s%c%c", FILE_LIST_BRACKET, fileInfo.fileName, FILE_LIST_BRACKET, FILE_LIST_SEPARATOR);
+ outBuf->catf("%c%s%c%c", FILE_LIST_BRACKET, fileInfo.fileName, FILE_LIST_BRACKET, FILE_LIST_SEPARATOR);
}
else
{
- fileResponse->catf("%s\n", fileInfo.fileName);
+ outBuf->catf("%s\n", fileInfo.fileName);
}
} while (platform.GetMassStorage()->FindNext(fileInfo));
if (encapsulateList)
{
// remove the last separator
- (*fileResponse)[fileResponse->Length() - 1] = 0;
+ (*outBuf)[outBuf->Length() - 1] = 0;
}
}
else
{
- fileResponse->cat("NONE\n");
+ outBuf->cat("NONE\n");
}
}
-
- UnlockAll(gb);
- HandleReply(gb, false, fileResponse);
- return true;
}
+ break;
case 21: // Initialise SD card
if (!LockFileSystem(gb)) // don't allow more than one at a time to avoid contention on output buffers
@@ -783,6 +780,7 @@ bool GCodes::HandleMcode(GCodeBuffer& gb, const StringRef& reply)
break;
case 226: // Gcode Initiated Pause
+ case 600: // Filament change pause
if (&gb == fileGCode) // ignore M226 if it did't come from within a file being printed
{
if (gb.IsDoingFileMacro())
@@ -795,7 +793,7 @@ bool GCodes::HandleMcode(GCodeBuffer& gb, const StringRef& reply)
{
return false;
}
- DoPause(gb, PauseReason::gcode, nullptr);
+ DoPause(gb, (code == 600) ? PauseReason::filamentChange : PauseReason::gcode, nullptr);
}
}
break;
@@ -903,15 +901,12 @@ bool GCodes::HandleMcode(GCodeBuffer& gb, const StringRef& reply)
{
String<MaxFilenameLength> filename;
const bool gotFilename = gb.GetUnprecedentedString(filename.GetRef());
- OutputBuffer *fileInfoResponse;
- const bool done = reprap.GetFileInfoResponse((gotFilename) ? filename.c_str() : nullptr, fileInfoResponse, false);
- if (done)
+ const bool done = reprap.GetFileInfoResponse((gotFilename) ? filename.c_str() : nullptr, outBuf, false);
+ if (outBuf != nullptr)
{
- fileInfoResponse->cat('\n');
- UnlockAll(gb);
- HandleReply(gb, false, fileInfoResponse);
+ outBuf->cat('\n');
}
- return done;
+ result = (done) ? GCodeResult::ok : GCodeResult::notFinished;
}
break;
@@ -1434,13 +1429,14 @@ bool GCodes::HandleMcode(GCodeBuffer& gb, const StringRef& reply)
if (!cancelWait)
{
+ const float tolerance = (gb.Seen('S')) ? max<float>(gb.GetFValue(), 0.1) : TEMPERATURE_CLOSE_ENOUGH;
bool seen = false;
if (gb.Seen('P'))
{
// Wait for the heaters associated with the specified tool to be ready
int toolNumber = gb.GetIValue();
toolNumber += gb.GetToolNumberAdjust();
- if (!ToolHeatersAtSetTemperatures(reprap.GetTool(toolNumber), true))
+ if (!ToolHeatersAtSetTemperatures(reprap.GetTool(toolNumber), true, tolerance))
{
CheckReportDue(gb, reply); // check whether we need to send a temperature or status report
isWaiting = true;
@@ -1458,7 +1454,7 @@ bool GCodes::HandleMcode(GCodeBuffer& gb, const StringRef& reply)
for (size_t i = 0; i < heaterCount; i++)
{
- if (!reprap.GetHeat().HeaterAtSetTemperature(heaters[i], true))
+ if (!reprap.GetHeat().HeaterAtSetTemperature(heaters[i], true, tolerance))
{
CheckReportDue(gb, reply); // check whether we need to send a temperature or status report
isWaiting = true;
@@ -1481,7 +1477,7 @@ bool GCodes::HandleMcode(GCodeBuffer& gb, const StringRef& reply)
for (size_t i = 0; i < NumChamberHeaters; i++)
{
const int8_t heater = reprap.GetHeat().GetChamberHeater(i);
- if (heater >= 0 && !reprap.GetHeat().HeaterAtSetTemperature(heater, true))
+ if (heater >= 0 && !reprap.GetHeat().HeaterAtSetTemperature(heater, true, tolerance))
{
CheckReportDue(gb, reply); // check whether we need to send a temperature or status report
isWaiting = true;
@@ -1497,7 +1493,7 @@ bool GCodes::HandleMcode(GCodeBuffer& gb, const StringRef& reply)
if (chamberIndices[i] >= 0 && chamberIndices[i] < NumChamberHeaters)
{
const int8_t heater = reprap.GetHeat().GetChamberHeater(chamberIndices[i]);
- if (heater >= 0 && !reprap.GetHeat().HeaterAtSetTemperature(heater, true))
+ if (heater >= 0 && !reprap.GetHeat().HeaterAtSetTemperature(heater, true, tolerance))
{
CheckReportDue(gb, reply); // check whether we need to send a temperature or status report
isWaiting = true;
@@ -1510,7 +1506,7 @@ bool GCodes::HandleMcode(GCodeBuffer& gb, const StringRef& reply)
}
// Wait for all heaters except chamber(s) to be ready
- if (!seen && !reprap.GetHeat().AllHeatersAtSetTemperatures(true))
+ if (!seen && !reprap.GetHeat().AllHeatersAtSetTemperatures(true, tolerance))
{
CheckReportDue(gb, reply); // check whether we need to send a temperature or status report
isWaiting = true;
@@ -1789,7 +1785,7 @@ bool GCodes::HandleMcode(GCodeBuffer& gb, const StringRef& reply)
reprap.GetHeat().SetActiveTemperature(heater, temperature);
reprap.GetHeat().Activate(heater);
- if (cancelWait || reprap.GetHeat().HeaterAtSetTemperature(heater, waitWhenCooling))
+ if (cancelWait || reprap.GetHeat().HeaterAtSetTemperature(heater, waitWhenCooling, TEMPERATURE_CLOSE_ENOUGH))
{
cancelWait = isWaiting = false;
break;
@@ -1925,6 +1921,8 @@ bool GCodes::HandleMcode(GCodeBuffer& gb, const StringRef& reply)
result = reprap.GetMove().ConfigureAccelerations(gb, reply);
break;
+ // For case 205 see case 566
+
case 206: // Offset axes
result = OffsetAxes(gb, reply);
break;
@@ -1973,14 +1971,21 @@ bool GCodes::HandleMcode(GCodeBuffer& gb, const StringRef& reply)
{
if (gb.Seen(axisLetters[axis]))
{
- const float value = gb.GetFValue() * distanceScale;
- if (setMin)
+ float values[2];
+ size_t numValues = 2;
+ gb.GetFloatArray(values, numValues, false);
+ if (numValues == 2)
+ {
+ platform.SetAxisMinimum(axis, values[0], gb.MachineState().runningM501);
+ platform.SetAxisMaximum(axis, values[1], gb.MachineState().runningM501);
+ }
+ else if (setMin)
{
- platform.SetAxisMinimum(axis, value, gb.MachineState().runningM501);
+ platform.SetAxisMinimum(axis, values[0], gb.MachineState().runningM501);
}
else
{
- platform.SetAxisMaximum(axis, value, gb.MachineState().runningM501);
+ platform.SetAxisMaximum(axis, values[0], gb.MachineState().runningM501);
}
seen = true;
}
@@ -1988,11 +1993,11 @@ bool GCodes::HandleMcode(GCodeBuffer& gb, const StringRef& reply)
if (!seen)
{
- reply.copy("Axis limits ");
- char sep = '-';
+ reply.copy("Axis limit");
+ char sep = 's';
for (size_t axis = 0; axis < numTotalAxes; axis++)
{
- reply.catf("%c %c: %.1f min, %.1f max", sep, axisLetters[axis], (double)platform.AxisMinimum(axis), (double)platform.AxisMaximum(axis));
+ reply.catf("%c %c%.1f:%.1f", sep, axisLetters[axis], (double)platform.AxisMinimum(axis), (double)platform.AxisMaximum(axis));
sep = ',';
}
}
@@ -2137,10 +2142,20 @@ bool GCodes::HandleMcode(GCodeBuffer& gb, const StringRef& reply)
{
return false;
}
+
const bool absolute = (gb.Seen('R') && gb.GetIValue() == 0);
- float difference = (absolute) ? fval - currentBabyStepZOffset : fval;
- difference = constrain<float>(difference, -1.0, 1.0);
- currentBabyStepZOffset += difference;
+ float difference;
+ if (absolute)
+ {
+ difference = fval - currentBabyStepZOffset;
+ currentBabyStepZOffset = fval;
+ }
+ else
+ {
+ difference = constrain<float>(fval, -1.0, 1.0);
+ currentBabyStepZOffset += difference;
+ }
+
const float amountPushed = reprap.GetMove().PushBabyStepping(difference);
moveBuffer.initialCoords[Z_AXIS] += amountPushed;
@@ -2531,22 +2546,47 @@ bool GCodes::HandleMcode(GCodeBuffer& gb, const StringRef& reply)
case 408: // Get status in JSON format
{
- const int type = gb.Seen('S') ? gb.GetIValue() : 0;
- const int seq = gb.Seen('R') ? gb.GetIValue() : -1;
- if (&gb == auxGCode && (type == 0 || type == 2))
+ const int form = gb.Seen('P') ? gb.GetIValue() : 0;
+ switch (form)
{
- lastAuxStatusReportType = type;
- }
+ case 0:
+ {
+ const int type = gb.Seen('S') ? gb.GetIValue() : 0;
+ const int seq = gb.Seen('R') ? gb.GetIValue() : -1;
+ if (&gb == auxGCode && (type == 0 || type == 2))
+ {
+ lastAuxStatusReportType = type;
+ }
- OutputBuffer * const statusResponse = GenerateJsonStatusResponse(type, seq, (&gb == auxGCode) ? ResponseSource::AUX : ResponseSource::Generic);
+ outBuf = GenerateJsonStatusResponse(type, seq, (&gb == auxGCode) ? ResponseSource::AUX : ResponseSource::Generic);
+ if (outBuf == nullptr)
+ {
+ result = GCodeResult::notFinished; // we ran out of buffers, so try again later
+ }
+ }
+ break;
- if (statusResponse != nullptr)
- {
- UnlockAll(gb);
- HandleReply(gb, false, statusResponse);
- return true;
+#if SUPPORT_OBJECT_MODEL
+ case 1:
+ {
+ String<MaxFilenameLength> filter;
+ bool dummy;
+ gb.TryGetQuotedString('F', filter.GetRef(), dummy);
+ if (!OutputBuffer::Allocate(outBuf))
+ {
+ result = GCodeResult::notFinished;
+ }
+ else
+ {
+ reprap.ReportAsJson(outBuf, filter.c_str(), ObjectModel::flagsNone);
+ }
+ }
+ break;
+#endif
+
+ default:
+ break;
}
- result = GCodeResult::notFinished; // we ran out of buffers, so try again later
}
break;
@@ -2690,9 +2730,8 @@ bool GCodes::HandleMcode(GCodeBuffer& gb, const StringRef& reply)
return false;
}
- // Need a valid output buffer to continue...
- OutputBuffer *configResponse;
- if (!OutputBuffer::Allocate(configResponse))
+ // Need a valid output buffer to continue
+ if (!OutputBuffer::Allocate(outBuf))
{
// No buffer available, try again later
return false;
@@ -2709,7 +2748,7 @@ bool GCodes::HandleMcode(GCodeBuffer& gb, const StringRef& reply)
{
char fileBuffer[FILE_BUFFER_SIZE];
size_t bytesRead,
- bytesLeftForWriting = OutputBuffer::GetBytesLeft(configResponse);
+ bytesLeftForWriting = OutputBuffer::GetBytesLeft(outBuf);
while ((bytesRead = f->Read(fileBuffer, FILE_BUFFER_SIZE)) > 0 && bytesLeftForWriting > 0)
{
// Don't write more data than we can process
@@ -2724,13 +2763,9 @@ bool GCodes::HandleMcode(GCodeBuffer& gb, const StringRef& reply)
}
// Write it
- configResponse->cat(fileBuffer, bytesRead);
+ outBuf->cat(fileBuffer, bytesRead);
}
f->Close();
-
- UnlockAll(gb);
- HandleReply(gb, false, configResponse);
- return true;
}
}
break;
@@ -2818,7 +2853,7 @@ bool GCodes::HandleMcode(GCodeBuffer& gb, const StringRef& reply)
if (gb.Seen('P'))
{
seen = true;
- uint8_t eth[4];
+ IPAddress eth;
if (gb.GetIPAddress(eth))
{
platform.SetIPAddress(eth);
@@ -2851,7 +2886,7 @@ bool GCodes::HandleMcode(GCodeBuffer& gb, const StringRef& reply)
{
if (gb.Seen('P'))
{
- uint8_t eth[4];
+ IPAddress eth;
if (gb.GetIPAddress(eth))
{
platform.SetNetMask(eth);
@@ -2864,8 +2899,8 @@ bool GCodes::HandleMcode(GCodeBuffer& gb, const StringRef& reply)
}
else
{
- const uint8_t * const nm = platform.NetMask();
- reply.printf("Net mask: %d.%d.%d.%d ", nm[0], nm[1], nm[2], nm[3]);
+ const IPAddress nm = platform.NetMask();
+ reply.printf("Net mask: %d.%d.%d.%d ", nm.GetQuad(0), nm.GetQuad(1), nm.GetQuad(2), nm.GetQuad(3));
}
}
break;
@@ -2875,7 +2910,7 @@ bool GCodes::HandleMcode(GCodeBuffer& gb, const StringRef& reply)
{
if (gb.Seen('P'))
{
- uint8_t eth[4];
+ IPAddress eth;
if (gb.GetIPAddress(eth))
{
platform.SetGateWay(eth);
@@ -2888,8 +2923,8 @@ bool GCodes::HandleMcode(GCodeBuffer& gb, const StringRef& reply)
}
else
{
- const uint8_t * const gw = platform.GateWay();
- reply.printf("Gateway: %d.%d.%d.%d ", gw[0], gw[1], gw[2], gw[3]);
+ const IPAddress gw = platform.GateWay();
+ reply.printf("Gateway: %d.%d.%d.%d ", gw.GetQuad(0), gw.GetQuad(1), gw.GetQuad(2), gw.GetQuad(3));
}
}
break;
@@ -3052,14 +3087,16 @@ bool GCodes::HandleMcode(GCodeBuffer& gb, const StringRef& reply)
}
break;
- case 566: // Set/print maximum jerk speeds
+ case 205: // Set/print maximum jerk speeds in mm/sec
+ case 566: // Set/print maximum jerk speeds in mm/min
{
+ const float multiplier = (code == 566) ? SecondsToMinutes * distanceScale : distanceScale;
bool seen = false;
for (size_t axis = 0; axis < numTotalAxes; axis++)
{
if (gb.Seen(axisLetters[axis]))
{
- platform.SetInstantDv(axis, gb.GetFValue() * distanceScale * SecondsToMinutes); // G Code feedrates are in mm/minute; we need mm/sec
+ platform.SetInstantDv(axis, gb.GetFValue() * multiplier);
seen = true;
}
}
@@ -3072,7 +3109,7 @@ bool GCodes::HandleMcode(GCodeBuffer& gb, const StringRef& reply)
gb.GetFloatArray(eVals, eCount, true);
for (size_t e = 0; e < eCount; e++)
{
- platform.SetInstantDv(numTotalAxes + e, eVals[e] * distanceScale * SecondsToMinutes);
+ platform.SetInstantDv(numTotalAxes + e, eVals[e] * multiplier);
}
}
else if (!seen)
@@ -3080,13 +3117,13 @@ bool GCodes::HandleMcode(GCodeBuffer& gb, const StringRef& reply)
reply.copy("Maximum jerk rates: ");
for (size_t axis = 0; axis < numTotalAxes; ++axis)
{
- reply.catf("%c: %.1f, ", axisLetters[axis], (double)(platform.GetInstantDv(axis) / (distanceScale * SecondsToMinutes)));
+ reply.catf("%c: %.1f, ", axisLetters[axis], (double)(platform.GetInstantDv(axis) / multiplier));
}
reply.cat("E:");
char sep = ' ';
for (size_t extruder = 0; extruder < numExtruders; extruder++)
{
- reply.catf("%c%.1f", sep, (double)(platform.GetInstantDv(extruder + numTotalAxes) / (distanceScale * SecondsToMinutes)));
+ reply.catf("%c%.1f", sep, (double)(platform.GetInstantDv(extruder + numTotalAxes) / multiplier));
sep = ':';
}
}
@@ -3388,7 +3425,7 @@ bool GCodes::HandleMcode(GCodeBuffer& gb, const StringRef& reply)
#if SUPPORT_INKJET
case 578: // Fire Inkjet bits
- if (!AllMovesAreFinishedAndMoveBufferIsLoaded())
+ if (!LockMovementAndWaitForStandstill())
{
return false;
}
@@ -3494,18 +3531,7 @@ bool GCodes::HandleMcode(GCodeBuffer& gb, const StringRef& reply)
case 589: // Configure access point
if (!gb.MachineState().runningM502) // when running M502 we don't execute network-related commands
{
- OutputBuffer *longReply = nullptr;
- result = reprap.GetNetwork().HandleWiFiCode(code, gb, reply, longReply);
- if (longReply != nullptr)
- {
- if (result == GCodeResult::ok)
- {
- UnlockAll(gb);
- HandleReply(gb, false, longReply);
- return true;
- }
- OutputBuffer::ReleaseAll(longReply);
- }
+ result = reprap.GetNetwork().HandleWiFiCode(code, gb, reply, outBuf);
}
break;
#endif
@@ -3548,6 +3574,8 @@ bool GCodes::HandleMcode(GCodeBuffer& gb, const StringRef& reply)
result = reprap.GetMove().ConfigureDynamicAcceleration(gb, reply);
break;
+ // For case 600, see 226
+
case 665: // Set delta configuration
if (!LockMovementAndWaitForStandstill(gb))
{
@@ -4082,7 +4110,7 @@ bool GCodes::HandleMcode(GCodeBuffer& gb, const StringRef& reply)
#if HAS_STALL_DETECT
case 915:
- result = GetGCodeResultFromError(platform.ConfigureStallDetection(gb, reply));
+ result = platform.ConfigureStallDetection(gb, reply, outBuf);
break;
#endif
@@ -4160,7 +4188,7 @@ bool GCodes::HandleMcode(GCodeBuffer& gb, const StringRef& reply)
break;
}
- return HandleResult(gb, result, reply);
+ return HandleResult(gb, result, reply, outBuf);
}
bool GCodes::HandleTcode(GCodeBuffer& gb, const StringRef& reply)
@@ -4178,10 +4206,20 @@ bool GCodes::HandleTcode(GCodeBuffer& gb, const StringRef& reply)
toolNum = gb.GetCommandNumber();
toolNum += gb.GetToolNumberAdjust();
}
- else if (gb.Seen('R') && gb.GetIValue() == 1)
+ else if (gb.Seen('R'))
{
- seen = true;
- toolNum = pauseRestorePoint.toolNumber;
+ const unsigned int rpNumber = gb.GetIValue();
+ if (rpNumber < ARRAY_SIZE(numberedRestorePoints))
+ {
+ seen = true;
+ toolNum = numberedRestorePoints[rpNumber].toolNumber;
+ }
+ else
+ {
+ UnlockAll(gb);
+ HandleReply(gb, GCodeResult::error, "T: bad restore point number");
+ return true; // bad restore point number so ignore the T command
+ }
}
if (seen)
@@ -4230,8 +4268,17 @@ bool GCodes::HandleTcode(GCodeBuffer& gb, const StringRef& reply)
}
// This is called to deal with the result of processing a G- or M-code
-bool GCodes::HandleResult(GCodeBuffer& gb, GCodeResult rslt, const StringRef& reply)
+bool GCodes::HandleResult(GCodeBuffer& gb, GCodeResult rslt, const StringRef& reply, OutputBuffer *outBuf)
{
+ if (outBuf != nullptr)
+ {
+ // We only have an OutputBuffer when rslt == GCodeResult::ok
+ gb.timerRunning = false;
+ UnlockAll(gb);
+ HandleReply(gb, outBuf);
+ return true;
+ }
+
switch (rslt)
{
case GCodeResult::notFinished:
diff --git a/src/GCodes/GCodes3.cpp b/src/GCodes/GCodes3.cpp
index de4a9fd8..5c3b96b9 100644
--- a/src/GCodes/GCodes3.cpp
+++ b/src/GCodes/GCodes3.cpp
@@ -117,6 +117,7 @@ GCodeResult GCodes::SavePosition(GCodeBuffer& gb,const StringRef& reply)
if (sParam < ARRAY_SIZE(numberedRestorePoints))
{
SavePosition(numberedRestorePoints[sParam], gb);
+ numberedRestorePoints[sParam].toolNumber = reprap.GetCurrentToolNumber();
return GCodeResult::ok;
}
@@ -223,45 +224,42 @@ GCodeResult GCodes::OffsetAxes(GCodeBuffer& gb, const StringRef& reply)
// Set workspace coordinates
GCodeResult GCodes::GetSetWorkplaceCoordinates(GCodeBuffer& gb, const StringRef& reply, bool compute)
{
- if (gb.Seen('P'))
+ const uint32_t cs = (gb.Seen('P')) ? gb.GetIValue() : currentCoordinateSystem + 1;
+ if (cs > 0 && cs <= NumCoordinateSystems)
{
- const uint32_t cs = gb.GetIValue();
- if (cs > 0 && cs <= NumCoordinateSystems)
+ bool seen = false;
+ for (size_t axis = 0; axis < numVisibleAxes; axis++)
{
- bool seen = false;
- for (size_t axis = 0; axis < numVisibleAxes; axis++)
+ if (gb.Seen(axisLetters[axis]))
{
- if (gb.Seen(axisLetters[axis]))
+ const float coord = gb.GetFValue() * distanceScale;
+ if (!seen)
{
- const float coord = gb.GetFValue() * distanceScale;
- if (!seen)
+ if (!LockMovementAndWaitForStandstill(gb)) // make sure the user coordinates are stable and up to date
{
- if (!LockMovementAndWaitForStandstill(gb)) // make sure the user coordinates are stable and up to date
- {
- return GCodeResult::notFinished;
- }
- seen = true;
+ return GCodeResult::notFinished;
}
- workplaceCoordinates[cs - 1][axis] = (compute)
- ? currentUserPosition[axis] - coord + workplaceCoordinates[currentCoordinateSystem][axis]
- : coord;
+ seen = true;
}
+ workplaceCoordinates[cs - 1][axis] = (compute)
+ ? currentUserPosition[axis] - coord + workplaceCoordinates[currentCoordinateSystem][axis]
+ : coord;
}
+ }
- if (seen)
- {
- ToolOffsetInverseTransform(moveBuffer.coords, currentUserPosition); // update user coordinates in case we are using the workspace we just changed
- }
- else
+ if (seen)
+ {
+ ToolOffsetInverseTransform(moveBuffer.coords, currentUserPosition); // update user coordinates in case we are using the workspace we just changed
+ }
+ else
+ {
+ reply.printf("Origin of workplace %" PRIu32 ":", cs);
+ for (size_t axis = 0; axis < numVisibleAxes; axis++)
{
- reply.printf("Origin of workplace %" PRIu32 ":", cs);
- for (size_t axis = 0; axis < numVisibleAxes; axis++)
- {
- reply.catf(" %c%.2f", axisLetters[axis], (double)(workplaceCoordinates[cs - 1][axis]/distanceScale));
- }
+ reply.catf(" %c%.2f", axisLetters[axis], (double)(workplaceCoordinates[cs - 1][axis]/distanceScale));
}
- return GCodeResult::ok;
}
+ return GCodeResult::ok;
}
return GCodeResult::badOrMissingParameter;
@@ -283,7 +281,7 @@ GCodeResult GCodes::DefineGrid(GCodeBuffer& gb, const StringRef &reply)
return GCodeResult::notFinished;
}
- bool seenX = false, seenY = false, seenR = false, seenS = false;
+ bool seenX = false, seenY = false, seenR = false, seenP = false, seenS = false;
float xValues[2];
float yValues[2];
float spacings[2] = { DefaultGridSpacing, DefaultGridSpacing };
@@ -296,10 +294,19 @@ GCodeResult GCodes::DefineGrid(GCodeBuffer& gb, const StringRef &reply)
{
return GCodeResult::error;
}
- if (gb.TryGetFloatArray('S', 2, spacings, reply, seenS, true))
+
+ uint32_t numPoints[2];
+ if (gb.TryGetUIArray('P', 2, numPoints, reply, seenP, true))
{
return GCodeResult::error;
}
+ if (!seenP)
+ {
+ if (gb.TryGetFloatArray('S', 2, spacings, reply, seenS, true))
+ {
+ return GCodeResult::error;
+ }
+ }
float radius = -1.0;
gb.TryGetFValue('R', radius, seenR);
@@ -327,20 +334,54 @@ GCodeResult GCodes::DefineGrid(GCodeBuffer& gb, const StringRef &reply)
if (!seenX && !seenR)
{
- // Must have given just the S parameter
+ // Must have given just the S or P parameter
reply.copy("specify at least radius or X,Y ranges in M577");
return GCodeResult::error;
}
- if (!seenX)
+ if (seenX)
+ {
+ // Seen both X and Y
+ if (seenP)
+ {
+ if (spacings[0] >= 2 && xValues[1] > xValues[0])
+ {
+ spacings[0] = (xValues[1] - xValues[0])/(numPoints[0] - 1);
+ }
+ if (spacings[1] >= 2 && yValues[1] > yValues[0])
+ {
+ spacings[1] = (yValues[1] - yValues[0])/(numPoints[1] - 1);
+ }
+ }
+ }
+ else
{
- if (radius > 0)
+ // Seen R
+ if (radius > 0.0)
{
- const float effectiveXRadius = floorf((radius - 0.1)/spacings[0]) * spacings[0];
+ float effectiveXRadius;
+ if (seenP && numPoints[0] >= 2)
+ {
+ effectiveXRadius = radius - 0.1;
+ spacings[0] = (2 * effectiveXRadius)/(numPoints[0] - 1);
+ }
+ else
+ {
+ effectiveXRadius = floorf((radius - 0.1)/spacings[0]) * spacings[0];
+ }
xValues[0] = -effectiveXRadius;
xValues[1] = effectiveXRadius + 0.1;
- const float effectiveYRadius = floorf((radius - 0.1)/spacings[1]) * spacings[1];
+ float effectiveYRadius;
+ if (seenP && numPoints[1] >= 2)
+ {
+ effectiveYRadius = radius - 0.1;
+ spacings[1] = (2 * effectiveYRadius)/(numPoints[1] - 1);
+ }
+ else
+ {
+ effectiveYRadius = floorf((radius - 0.1)/spacings[1]) * spacings[1];
+ }
yValues[0] = -effectiveYRadius;
yValues[1] = effectiveYRadius + 0.1;
}
@@ -431,61 +472,92 @@ GCodeResult GCodes::ChangeSimulationMode(GCodeBuffer& gb, const StringRef &reply
// Handle M558
GCodeResult GCodes::SetOrReportZProbe(GCodeBuffer& gb, const StringRef &reply)
{
- bool seenType = false, seenParam = false;
+ bool seen = false;
// We must get and set the Z probe type first before setting the dive height etc., because different probe types may have different parameters
+ uint32_t requestedChannel = 0;
if (gb.Seen('P')) // probe type
{
- platform.SetZProbeType(gb.GetIValue());
- seenType = true;
- DoDwellTime(gb, 100); // delay a little to allow the averaging filters to accumulate data from the new source
+ seen = true;
+ uint32_t requestedType = gb.GetUIValue();
+ switch (requestedType)
+ {
+ case (uint32_t)ZProbeType::endstopSwitch:
+ requestedChannel = E0_AXIS; // default channel if no C parameter present
+ break;
+
+ case (uint32_t)ZProbeType::e1Switch_obsolete:
+ requestedChannel = E0_AXIS + 1;
+ requestedType = (uint32_t)ZProbeType::endstopSwitch;
+ break;
+
+ case (uint32_t)ZProbeType::zSwitch_obsolete:
+ requestedChannel = Z_AXIS;
+ requestedType = (uint32_t)ZProbeType::endstopSwitch;
+ break;
+
+ default:
+ break;
+ }
+ platform.SetZProbeType(requestedType);
+ DoDwellTime(gb, 100); // delay a little to allow the averaging filters to accumulate data from the new source
+ }
+
+ // Do the input channel next so that 'seen' will be true only if the type and/or the channel has been specified
+ if (gb.Seen('C')) // input channel
+ {
+ requestedChannel = gb.GetUIValue();
+ seen = true;
}
ZProbe params = platform.GetCurrentZProbeParameters();
- gb.TryGetFValue('H', params.diveHeight, seenParam); // dive height
+ if (seen) // if seen P and/or C
+ {
+ params.inputChannel = requestedChannel; // set the input to the default one for this type or the requested one
+ }
- if (gb.Seen('F')) // feed rate i.e. probing speed
+ gb.TryGetFValue('H', params.diveHeight, seen); // dive height
+ if (gb.Seen('F')) // feed rate i.e. probing speed
{
params.probeSpeed = gb.GetFValue() * SecondsToMinutes;
- seenParam = true;
+ seen = true;
}
if (gb.Seen('T')) // travel speed to probe point
{
params.travelSpeed = gb.GetFValue() * SecondsToMinutes;
- seenParam = true;
+ seen = true;
}
if (gb.Seen('I'))
{
params.invertReading = (gb.GetIValue() != 0);
- seenParam = true;
+ seen = true;
}
if (gb.Seen('B'))
{
params.turnHeatersOff = (gb.GetIValue() == 1);
- seenParam = true;
+ seen = true;
}
- gb.TryGetFValue('R', params.recoveryTime, seenParam); // Z probe recovery time
- gb.TryGetFValue('S', params.tolerance, seenParam); // tolerance when multi-tapping
+ gb.TryGetFValue('R', params.recoveryTime, seen); // Z probe recovery time
+ gb.TryGetFValue('S', params.tolerance, seen); // tolerance when multi-tapping
if (gb.Seen('A'))
{
params.maxTaps = gb.GetUIValue();
- seenParam = true;
+ seen = true;
}
- if (seenParam)
+ if (seen)
{
platform.SetZProbeParameters(platform.GetZProbeType(), params);
}
-
- if (!(seenType || seenParam))
+ else
{
- reply.printf("Z Probe type %u, invert %s, dive height %.1fmm, probe speed %dmm/min, travel speed %dmm/min, recovery time %.2f sec, heaters %s, max taps %u, max diff %.2f",
- (unsigned int)platform.GetZProbeType(), (params.invertReading) ? "yes" : "no", (double)params.diveHeight,
+ reply.printf("Z Probe type %u, input %u, invert %s, dive height %.1fmm, probe speed %dmm/min, travel speed %dmm/min, recovery time %.2f sec, heaters %s, max taps %u, max diff %.2f",
+ (unsigned int)platform.GetZProbeType(), params.inputChannel, (params.invertReading) ? "yes" : "no", (double)params.diveHeight,
(int)(params.probeSpeed * MinutesToSeconds), (int)(params.travelSpeed * MinutesToSeconds),
(double)params.recoveryTime,
(params.turnHeatersOff) ? "suspended" : "normal",
diff --git a/src/Heating/Heat.cpp b/src/Heating/Heat.cpp
index 3fb88247..47258304 100644
--- a/src/Heating/Heat.cpp
+++ b/src/Heating/Heat.cpp
@@ -257,11 +257,11 @@ void Heat::Diagnostics(MessageType mtype)
}
}
-bool Heat::AllHeatersAtSetTemperatures(bool includingBed) const
+bool Heat::AllHeatersAtSetTemperatures(bool includingBed, float tolerance) const
{
for (size_t heater : ARRAY_INDICES(pids))
{
- if (!HeaterAtSetTemperature(heater, true) && (includingBed || !IsBedHeater(heater)))
+ if (!HeaterAtSetTemperature(heater, true, tolerance) && (includingBed || !IsBedHeater(heater)))
{
return false;
}
@@ -270,7 +270,7 @@ bool Heat::AllHeatersAtSetTemperatures(bool includingBed) const
}
//query an individual heater
-bool Heat::HeaterAtSetTemperature(int8_t heater, bool waitWhenCooling) const
+bool Heat::HeaterAtSetTemperature(int8_t heater, bool waitWhenCooling, float tolerance) const
{
// If it hasn't anything to do, it must be right wherever it is...
if (heater < 0 || heater >= (int)NumHeaters || pids[heater]->SwitchedOff() || pids[heater]->FaultOccurred())
@@ -281,7 +281,7 @@ bool Heat::HeaterAtSetTemperature(int8_t heater, bool waitWhenCooling) const
const float dt = GetTemperature(heater);
const float target = (pids[heater]->Active()) ? GetActiveTemperature(heater) : GetStandbyTemperature(heater);
return (target < TEMPERATURE_LOW_SO_DONT_CARE)
- || (fabsf(dt - target) <= TEMPERATURE_CLOSE_ENOUGH)
+ || (fabsf(dt - target) <= tolerance)
|| (target < dt && !waitWhenCooling);
}
diff --git a/src/Heating/Heat.h b/src/Heating/Heat.h
index c139f4a6..2bd56bd3 100644
--- a/src/Heating/Heat.h
+++ b/src/Heating/Heat.h
@@ -83,8 +83,9 @@ public:
void SwitchOff(int8_t heater); // Turn off a specific heater
void SwitchOffAll(bool includingChamberAndBed); // Turn all heaters off
void ResetFault(int8_t heater); // Reset a heater fault - only call this if you know what you are doing
- bool AllHeatersAtSetTemperatures(bool includingBed) const; // Is everything at temperature within tolerance?
- bool HeaterAtSetTemperature(int8_t heater, bool waitWhenCooling) const; // Is a specific heater at temperature within tolerance?
+ bool AllHeatersAtSetTemperatures(bool includingBed, float tolerance) const; // Is everything at temperature within tolerance?
+ bool HeaterAtSetTemperature(int8_t heater, bool waitWhenCooling, float tolerance) const;
+ // Is a specific heater at temperature within tolerance?
void Diagnostics(MessageType mtype); // Output useful information
float GetAveragePWM(size_t heater) const // Return the running average PWM to the heater as a fraction in [0, 1].
diff --git a/src/Heating/Sensors/CurrentLoopTemperatureSensor.cpp b/src/Heating/Sensors/CurrentLoopTemperatureSensor.cpp
index 66d683ae..b93a43a9 100644
--- a/src/Heating/Sensors/CurrentLoopTemperatureSensor.cpp
+++ b/src/Heating/Sensors/CurrentLoopTemperatureSensor.cpp
@@ -20,7 +20,7 @@ const uint32_t MinimumReadInterval = 100; // minimum interval between reads, in
CurrentLoopTemperatureSensor::CurrentLoopTemperatureSensor(unsigned int channel)
: SpiTemperatureSensor(channel, "Current Loop", channel - FirstLinearAdcChannel, MCP3204_SpiMode, MCP3204_Frequency),
- tempAt4mA(DefaultTempAt4mA), tempAt20mA(DefaultTempAt20mA), chipChannel(DefaultChipChannel), singleDifferential(DefaultSingleDifferential)
+ tempAt4mA(DefaultTempAt4mA), tempAt20mA(DefaultTempAt20mA), chipChannel(DefaultChipChannel), isDifferential(false)
{
CalcDerivedParameters();
}
@@ -56,8 +56,8 @@ GCodeResult CurrentLoopTemperatureSensor::Configure(unsigned int mCode, unsigned
bool seen = false;
gb.TryGetFValue('L', tempAt4mA, seen);
gb.TryGetFValue('H', tempAt20mA, seen);
- gb.TryGetFValue('C', chipChannel, seen);
- gb.TryGetFValue('W', singleDifferential, seen);
+ gb.TryGetUIValue('C', chipChannel, seen);
+ gb.TryGetUIValue('D', isDifferential, seen);
TryConfigureHeaterName(gb, seen);
if (seen)
@@ -117,9 +117,7 @@ void CurrentLoopTemperatureSensor::TryGetLinearAdcTemperature()
* These values represent clocks 1 to 5.
*/
- unsigned int channelByte = 0xC0 + chipChannel * 0x08;
- if ( singleDifferential == 1 )
- channelByte -= 0x40;
+ const uint8_t channelByte = ((isDifferential) ? 0x80 : 0xC0) | (chipChannel * 0x08);
static const uint8_t adcData[] = { channelByte, 0x00, 0x00 };
uint32_t rawVal;
lastResult = DoSpiTransaction(adcData, 3, rawVal);
diff --git a/src/Heating/Sensors/CurrentLoopTemperatureSensor.h b/src/Heating/Sensors/CurrentLoopTemperatureSensor.h
index 49b34b0a..0e3c85fa 100644
--- a/src/Heating/Sensors/CurrentLoopTemperatureSensor.h
+++ b/src/Heating/Sensors/CurrentLoopTemperatureSensor.h
@@ -24,15 +24,14 @@ private:
// Configurable parameters
float tempAt4mA, tempAt20mA;
- unsigned int chipChannel, singleDifferential;
+ uint32_t chipChannel, isDifferential;
// Derived parameters
float minLinearAdcTemp, linearAdcDegCPerCount;
static constexpr float DefaultTempAt4mA = 385.0;
static constexpr float DefaultTempAt20mA = 1600.0;
- static constexpr int DefaultChipChannel = 0;
- static constexpr int DefaultSingleDifferential = 0;
+ static constexpr uint32_t DefaultChipChannel = 0;
};
#endif /* SRC_HEATING_LINEARADCTEMPERATURESENSOR_H_ */
diff --git a/src/Movement/BedProbing/Grid.cpp b/src/Movement/BedProbing/Grid.cpp
index 3f598706..79c1031a 100644
--- a/src/Movement/BedProbing/Grid.cpp
+++ b/src/Movement/BedProbing/Grid.cpp
@@ -17,6 +17,24 @@ const char * const GridDefinition::HeightMapLabelLines[] =
"xmin,xmax,ymin,ymax,radius,xspacing,yspacing,xnum,ynum" // current version label line
};
+#if SUPPORT_OBJECT_MODEL
+
+// Object model table and functions
+// Note: if using GCC version 7.3.1 20180622 and lambda functions are used in this table, you must compile this file with option -std=gnu++17.
+// Otherwise the table will be allocated in RAM instead of flash, which wastes too much RAM.
+
+// Macro to build a standard lambda function that includes the necessary type conversions
+#define OBJECT_MODEL_FUNC(_ret) OBJECT_MODEL_FUNC_BODY(GridDefinition, _ret)
+
+const ObjectModelTableEntry GridDefinition::objectModelTable[] =
+{
+ { "radius", OBJECT_MODEL_FUNC(&(self->radius)), TYPE_OF(float), ObjectModelTableEntry::none }
+};
+
+DEFINE_GET_OBJECT_MODEL_TABLE(GridDefinition)
+
+#endif
+
// Initialise the grid to be invalid
GridDefinition::GridDefinition()
: xMin(0.0), xMax(-1.0), yMin(0.0), yMax(-1.0), radius(-1.0), xSpacing(0.0), ySpacing(0.0)
diff --git a/src/Movement/BedProbing/Grid.h b/src/Movement/BedProbing/Grid.h
index 685933b7..bccddf88 100644
--- a/src/Movement/BedProbing/Grid.h
+++ b/src/Movement/BedProbing/Grid.h
@@ -9,9 +9,10 @@
#define SRC_MOVEMENT_GRID_H_
#include "RepRapFirmware.h"
+#include "ObjectModel/ObjectModel.h"
// This class defines the bed probing grid
-class GridDefinition
+class GridDefinition INHERIT_OBJECT_MODEL
{
public:
friend class HeightMap;
@@ -35,6 +36,9 @@ public:
void PrintError(float originalXrange, float originalYrange, const StringRef& r) const
pre(!IsValid());
+protected:
+ DECLARE_OBJECT_MODEL
+
private:
void CheckValidity();
diff --git a/src/Movement/BedProbing/RandomProbePointSet.cpp b/src/Movement/BedProbing/RandomProbePointSet.cpp
index 3ea421f5..4b49e5c4 100644
--- a/src/Movement/BedProbing/RandomProbePointSet.cpp
+++ b/src/Movement/BedProbing/RandomProbePointSet.cpp
@@ -9,6 +9,24 @@
#include "RepRap.h"
#include "Platform.h"
+#if SUPPORT_OBJECT_MODEL
+
+// Object model table and functions
+// Note: if using GCC version 7.3.1 20180622 and lambda functions are used in this table, you must compile this file with option -std=gnu++17.
+// Otherwise the table will be allocated in RAM instead of flash, which wastes too much RAM.
+
+// Macro to build a standard lambda function that includes the necessary type conversions
+#define OBJECT_MODEL_FUNC(_ret) OBJECT_MODEL_FUNC_BODY(RandomProbePointSet, _ret)
+
+const ObjectModelTableEntry RandomProbePointSet::objectModelTable[] =
+{
+ { "numBedCompensationPoints", OBJECT_MODEL_FUNC(&(self->numBedCompensationPoints)), TYPE_OF(uint32_t), ObjectModelTableEntry::none }
+};
+
+DEFINE_GET_OBJECT_MODEL_TABLE(RandomProbePointSet)
+
+#endif
+
RandomProbePointSet::RandomProbePointSet() : numBedCompensationPoints(0)
{
for (size_t point = 0; point < MaxProbePoints; point++)
diff --git a/src/Movement/BedProbing/RandomProbePointSet.h b/src/Movement/BedProbing/RandomProbePointSet.h
index de095f6f..49360ff5 100644
--- a/src/Movement/BedProbing/RandomProbePointSet.h
+++ b/src/Movement/BedProbing/RandomProbePointSet.h
@@ -9,8 +9,9 @@
#define SRC_MOVEMENT_RANDOMPROBEPOINTSET_H_
#include "RepRapFirmware.h"
+#include "ObjectModel/ObjectModel.h"
-class RandomProbePointSet
+class RandomProbePointSet INHERIT_OBJECT_MODEL
{
public:
RandomProbePointSet();
@@ -44,6 +45,9 @@ public:
void ReportProbeHeights(size_t numPoints, const StringRef& reply) const; // Print out the probe heights and any errors
void DebugPrint(size_t numPoints) const;
+protected:
+ DECLARE_OBJECT_MODEL
+
private:
bool GoodProbePointOrdering(size_t numPoints) const; // Check that the probe points are in the right order
float SecondDegreeTransformZ(float x, float y) const; // Used for second degree bed equation
@@ -62,7 +66,7 @@ private:
probeError = 8
};
- unsigned int numBedCompensationPoints; // The number of points we are actually using for bed compensation, 0 means identity bed transform
+ uint32_t numBedCompensationPoints; // The number of points we are actually using for bed compensation, 0 means identity bed transform
// Variables used to report what has been probed
float xBedProbePoints[MaxProbePoints]; // The X coordinates of the points on the bed at which to probe
diff --git a/src/Movement/DDA.cpp b/src/Movement/DDA.cpp
index c3ec0e71..51068b79 100644
--- a/src/Movement/DDA.cpp
+++ b/src/Movement/DDA.cpp
@@ -1361,18 +1361,23 @@ void DDA::Prepare(uint8_t simMode)
}
}
}
- else if (drive >= NumDirectDrivers)
+ else
{
- CanInterface::AddMovement(*this, params, drive - NumDirectDrivers, *pdm);
+ const uint8_t driver = platform.GetExtruderDriver(drive - numAxes);
+ if (driver >= NumDirectDrivers)
+ {
+ CanInterface::AddMovement(*this, params, driver - NumDirectDrivers, *pdm);
+ }
}
}
#endif
}
}
- moveStartTime = (reprap.GetMove().GetCurrentDDA() == nullptr) // if no move currently executing then this one will be the first...
- ? StepTimer::GetInterruptClocks() + MovementStartDelayClocks // ...so start this move after a short delay
- : prev->moveStartTime + prev->clocksNeeded; // else calculate the start time, assuming no more hiccups
+ const DDAState st = prev->state;
+ moveStartTime = (st == DDAState::executing || st == DDAState::frozen)
+ ? prev->moveStartTime + prev->clocksNeeded // this move will follow the previous one, so calculate the start time assuming no more hiccups
+ : StepTimer::GetInterruptClocks() + MovementStartDelayClocks; // else this move is the first so start it after a short delay
#if SUPPORT_CAN_EXPANSION
CanInterface::FinishMovement(moveStartTime);
@@ -1635,18 +1640,17 @@ pre(state == frozen)
}
#endif
- if (firstDM != nullptr)
- {
-
#if SUPPORT_LASER
- // Deal with laser power
- if (reprap.GetGCodes().GetMachineType() == MachineType::laser)
- {
- // Ideally we should ramp up the laser power as the machine accelerates, but for now we don't.
- reprap.GetPlatform().SetLaserPwm(laserPwmOrIoBits.laserPwm);
- }
+ // Deal with laser power
+ if (reprap.GetGCodes().GetMachineType() == MachineType::laser)
+ {
+ // Ideally we should ramp up the laser power as the machine accelerates, but for now we don't.
+ reprap.GetPlatform().SetLaserPwm(laserPwmOrIoBits.laserPwm);
+ }
#endif
+ if (firstDM != nullptr)
+ {
unsigned int extrusions = 0, retractions = 0; // bitmaps of extruding and retracting drives
const size_t numAxes = reprap.GetGCodes().GetTotalAxes();
for (size_t i = 0; i < NumDirectDrivers; ++i)
@@ -1817,8 +1821,13 @@ bool DDA::Step()
const uint32_t delayClocks = (clocksTaken + DDA::MinInterruptInterval) - (nextStepDue - isrStartTime);
moveStartTime += delayClocks;
nextStepDue += delayClocks;
+ for (DDA *nextDda = next; nextDda->state == DDAState::frozen; nextDda = nextDda->next)
+ {
+ nextDda->moveStartTime += delayClocks;
+ }
++numHiccups;
hadHiccup = true;
+ // TODO tell CAN drivers about the hiccup
}
// 8. Schedule next interrupt, or if it would be too soon, generate more steps immediately
diff --git a/src/Movement/DriveMovement.h b/src/Movement/DriveMovement.h
index 2d154816..c0ed0cc6 100644
--- a/src/Movement/DriveMovement.h
+++ b/src/Movement/DriveMovement.h
@@ -326,8 +326,8 @@ inline void DriveMovement::Release(DriveMovement *item)
// Get the current full step interval for this axis or extruder
inline uint32_t DriveMovement::GetStepInterval(uint32_t microstepShift) const
{
- return ((nextStep >> microstepShift) != 0) // if at least 1 full step done
- ? stepInterval << microstepShift // return the interval between steps converted to full steps
+ return (nextStep < totalSteps && nextStep > (1u << microstepShift)) // if at least 1 full step done
+ ? stepInterval << microstepShift // return the interval between steps converted to full steps
: 0;
}
diff --git a/src/Movement/Kinematics/HangprinterKinematics.cpp b/src/Movement/Kinematics/HangprinterKinematics.cpp
index f7c066a0..2cfdec8f 100644
--- a/src/Movement/Kinematics/HangprinterKinematics.cpp
+++ b/src/Movement/Kinematics/HangprinterKinematics.cpp
@@ -217,9 +217,10 @@ void HangprinterKinematics::GetAssumedInitialPosition(size_t numAxes, float posi
// This function is called when a request is made to home the axes in 'toBeHomed' and the axes in 'alreadyHomed' have already been homed.
// If we can proceed with homing some axes, return the name of the homing file to be called.
// If we can't proceed because other axes need to be homed first, return nullptr and pass those axes back in 'mustBeHomedFirst'.
-const char* HangprinterKinematics::GetHomingFileName(AxesBitmap toBeHomed, AxesBitmap alreadyHomed, size_t numVisibleAxes, AxesBitmap& mustHomeFirst) const
+AxesBitmap HangprinterKinematics::GetHomingFileName(AxesBitmap toBeHomed, AxesBitmap alreadyHomed, size_t numVisibleAxes, const StringRef& filename) const
{
- return "homeall.g";
+ filename.copy("homeall.g");
+ return 0;
}
// This function is called from the step ISR when an endstop switch is triggered during homing.
diff --git a/src/Movement/Kinematics/HangprinterKinematics.h b/src/Movement/Kinematics/HangprinterKinematics.h
index 96ceb9ef..aa4a7cbe 100644
--- a/src/Movement/Kinematics/HangprinterKinematics.h
+++ b/src/Movement/Kinematics/HangprinterKinematics.h
@@ -33,7 +33,7 @@ public:
HomingMode GetHomingMode() const override { return homeIndividualMotors; }
AxesBitmap AxesAssumedHomed(AxesBitmap g92Axes) const override;
AxesBitmap MustBeHomedAxes(AxesBitmap axesMoving, bool disallowMovesBeforeHoming) const override;
- const char* GetHomingFileName(AxesBitmap toBeHomed, AxesBitmap alreadyHomed, size_t numVisibleAxes, AxesBitmap& mustHomeFirst) const override;
+ AxesBitmap GetHomingFileName(AxesBitmap toBeHomed, AxesBitmap alreadyHomed, size_t numVisibleAxes, const StringRef& filename) const override;
bool QueryTerminateHomingMove(size_t axis) const override;
void OnHomingSwitchTriggered(size_t axis, bool highEnd, const float stepsPerMm[], DDA& dda) const override;
bool WriteResumeSettings(FileStore *f) const override;
diff --git a/src/Movement/Kinematics/Kinematics.cpp b/src/Movement/Kinematics/Kinematics.cpp
index 145c466a..403ef67f 100644
--- a/src/Movement/Kinematics/Kinematics.cpp
+++ b/src/Movement/Kinematics/Kinematics.cpp
@@ -22,7 +22,6 @@
#include "GCodes/GCodes.h"
const char * const Kinematics::HomeAllFileName = "homeall.g";
-const char * const Kinematics::StandardHomingFileNames[] = AXES_("homex.g", "homey.g", "homez.g", "homeu.g", "homev.g", "homew.g", "homea.g", "homeb.g", "homec.g");
// Constructor. Pass segsPerSecond <= 0.0 to get non-segmented kinematics.
Kinematics::Kinematics(KinematicsType t, float segsPerSecond, float minSegLength, bool doUseRawG0)
@@ -104,12 +103,13 @@ void Kinematics::GetAssumedInitialPosition(size_t numAxes, float positions[]) co
// If we can proceed with homing some axes, return the name of the homing file to be called.
// If we can't proceed because other axes need to be homed first, return nullptr and pass those axes back in 'mustBeHomedFirst'.
// This default is suitable for most kinematics.
-const char* Kinematics::GetHomingFileName(AxesBitmap toBeHomed, AxesBitmap alreadyHomed, size_t numVisibleAxes, AxesBitmap& mustHomeFirst) const
+AxesBitmap Kinematics::GetHomingFileName(AxesBitmap toBeHomed, AxesBitmap alreadyHomed, size_t numVisibleAxes, const StringRef& filename) const
{
const AxesBitmap allAxes = LowestNBits<AxesBitmap>(numVisibleAxes);
if ((toBeHomed & allAxes) == allAxes)
{
- return HomeAllFileName;
+ filename.copy(HomeAllFileName);
+ return 0;
}
// If Z homing is done using a Z probe then X and Y must be homed before Z
@@ -117,26 +117,19 @@ const char* Kinematics::GetHomingFileName(AxesBitmap toBeHomed, AxesBitmap alrea
const AxesBitmap homeFirst = AxesToHomeBeforeProbing();
// Return the homing file for the lowest axis that we have been asked to home
- const char * const axisNames = reprap.GetGCodes().GetAxisLetters();
- const char lettersToTry[] = "XYZUVWABC";
- static_assert(ARRAY_SIZE(lettersToTry) >= MaxAxes, "lettersToTry too short");
for (size_t axis = 0; axis < numVisibleAxes; ++axis)
{
if (IsBitSet(toBeHomed, axis) && (axis != Z_AXIS || !homeZLast || (alreadyHomed & homeFirst) == homeFirst))
{
- for (size_t actualAxis = 0; actualAxis < MaxAxes; actualAxis++)
- {
- if (axisNames[axis] == lettersToTry[actualAxis])
- {
- return StandardHomingFileNames[actualAxis];
- }
- }
+ filename.copy("home");
+ filename.cat(tolower(reprap.GetGCodes().GetAxisLetters()[axis]));
+ filename.cat(".g");
+ return 0;
}
}
// Error, we can't home any axes that we were asked to home. It can only be because we can't home the Z axis.
- mustHomeFirst = homeFirst & ~alreadyHomed;
- return nullptr;
+ return homeFirst & ~alreadyHomed;
}
/*static*/ Kinematics *Kinematics::Create(KinematicsType k)
diff --git a/src/Movement/Kinematics/Kinematics.h b/src/Movement/Kinematics/Kinematics.h
index cca10d1e..7b4093e8 100644
--- a/src/Movement/Kinematics/Kinematics.h
+++ b/src/Movement/Kinematics/Kinematics.h
@@ -131,10 +131,10 @@ public:
virtual const char* HomingButtonNames() const { return "XYZUVWABC"; }
// This function is called when a request is made to home the axes in 'toBeHomed' and the axes in 'alreadyHomed' have already been homed.
- // If we can proceed with homing some axes, return the name of the homing file to be called. Optionally, update 'alreadyHomed' to indicate
+ // If we can't proceed because other axes need to be homed first, return those axes.
+ // If we can proceed with homing some axes, set 'filename' to the name of the homing file to be called and return 0. Optionally, update 'alreadyHomed' to indicate
// that some additional axes should be considered not homed.
- // If we can't proceed because other axes need to be homed first, return nullptr and pass those axes back in 'mustBeHomedFirst'.
- virtual const char* GetHomingFileName(AxesBitmap toBeHomed, AxesBitmap alreadyHomed, size_t numVisibleAxes, AxesBitmap& mustHomeFirst) const;
+ virtual AxesBitmap GetHomingFileName(AxesBitmap toBeHomed, AxesBitmap alreadyHomed, size_t numVisibleAxes, const StringRef& filename) const;
// This function is called from the step ISR when an endstop switch is triggered during homing.
// Return true if the entire homing move should be terminated, false if only the motor associated with the endstop switch should be stopped.
@@ -196,7 +196,6 @@ protected:
float minSegmentLength; // if we are using segmentation, the minimum segment size
static const char * const HomeAllFileName;
- static const char * const StandardHomingFileNames[];
private:
bool useSegmentation; // true if we have to approximate linear movement using segmentation
diff --git a/src/Movement/Kinematics/LinearDeltaKinematics.cpp b/src/Movement/Kinematics/LinearDeltaKinematics.cpp
index c5c69b26..47e5b887 100644
--- a/src/Movement/Kinematics/LinearDeltaKinematics.cpp
+++ b/src/Movement/Kinematics/LinearDeltaKinematics.cpp
@@ -689,25 +689,16 @@ AxesBitmap LinearDeltaKinematics::MustBeHomedAxes(AxesBitmap axesMoving, bool di
// This function is called when a request is made to home the axes in 'toBeHomed' and the axes in 'alreadyHomed' have already been homed.
// If we can proceed with homing some axes, return the name of the homing file to be called.
// If we can't proceed because other axes need to be homed first, return nullptr and pass those axes back in 'mustBeHomedFirst'.
-const char* LinearDeltaKinematics::GetHomingFileName(AxesBitmap toBeHomed, AxesBitmap alreadyHomed, size_t numVisibleAxes, AxesBitmap& mustHomeFirst) const
+AxesBitmap LinearDeltaKinematics::GetHomingFileName(AxesBitmap toBeHomed, AxesBitmap alreadyHomed, size_t numVisibleAxes, const StringRef& filename) const
{
// If homing X, Y or Z we must home all the towers
if ((toBeHomed & LowestNBits<AxesBitmap>(DELTA_AXES)) != 0)
{
- return "homedelta.g";
+ filename.copy("homedelta.g");
+ return 0;
}
- // Return the homing file for the lowest axis that we have been asked to home
- for (size_t axis = DELTA_AXES; axis < numVisibleAxes; ++axis)
- {
- if (IsBitSet(toBeHomed, axis))
- {
- return StandardHomingFileNames[axis];
- }
- }
-
- mustHomeFirst = 0;
- return nullptr;
+ return Kinematics::GetHomingFileName(toBeHomed, alreadyHomed, numVisibleAxes, filename);
}
// This function is called from the step ISR when an endstop switch is triggered during homing.
diff --git a/src/Movement/Kinematics/LinearDeltaKinematics.h b/src/Movement/Kinematics/LinearDeltaKinematics.h
index a17ee520..8a98de35 100644
--- a/src/Movement/Kinematics/LinearDeltaKinematics.h
+++ b/src/Movement/Kinematics/LinearDeltaKinematics.h
@@ -39,7 +39,7 @@ public:
HomingMode GetHomingMode() const override { return homeIndividualMotors; }
AxesBitmap AxesAssumedHomed(AxesBitmap g92Axes) const override;
AxesBitmap MustBeHomedAxes(AxesBitmap axesMoving, bool disallowMovesBeforeHoming) const override;
- const char* GetHomingFileName(AxesBitmap toBeHomed, AxesBitmap alreadyHomed, size_t numVisibleAxes, AxesBitmap& mustHomeFirst) const override;
+ AxesBitmap GetHomingFileName(AxesBitmap toBeHomed, AxesBitmap alreadyHomed, size_t numVisibleAxes, const StringRef& filename) const override;
bool QueryTerminateHomingMove(size_t axis) const override;
void OnHomingSwitchTriggered(size_t axis, bool highEnd, const float stepsPerMm[], DDA& dda) const override;
bool WriteResumeSettings(FileStore *f) const override;
diff --git a/src/Movement/Kinematics/PolarKinematics.cpp b/src/Movement/Kinematics/PolarKinematics.cpp
index 03f35bb9..9c0f01db 100644
--- a/src/Movement/Kinematics/PolarKinematics.cpp
+++ b/src/Movement/Kinematics/PolarKinematics.cpp
@@ -205,19 +205,23 @@ AxesBitmap PolarKinematics::MustBeHomedAxes(AxesBitmap axesMoving, bool disallow
// If we can proceed with homing some axes, return the name of the homing file to be called. Optionally, update 'alreadyHomed' to indicate
// that some additional axes should be considered not homed.
// If we can't proceed because other axes need to be homed first, return nullptr and pass those axes back in 'mustBeHomedFirst'.
-const char* PolarKinematics::GetHomingFileName(AxesBitmap toBeHomed, AxesBitmap alreadyHomed, size_t numVisibleAxes, AxesBitmap& mustHomeFirst) const
+AxesBitmap PolarKinematics::GetHomingFileName(AxesBitmap toBeHomed, AxesBitmap alreadyHomed, size_t numVisibleAxes, const StringRef& filename) const
{
// Ask the base class which homing file we should call first
- const char* ret = Kinematics::GetHomingFileName(toBeHomed, alreadyHomed, numVisibleAxes, mustHomeFirst);
- // Change the returned name if it is X or Y
- if (ret == StandardHomingFileNames[X_AXIS])
+ AxesBitmap ret = Kinematics::GetHomingFileName(toBeHomed, alreadyHomed, numVisibleAxes, filename);
+ if (ret == 0)
{
- ret = HomeRadiusFileName;
- }
- else if (ret == StandardHomingFileNames[Y_AXIS])
- {
- ret = HomeBedFileName;
+ // Change the returned name if it is X or Y
+ if (StringEquals(filename.c_str(), "homex.g"))
+ {
+ filename.copy(HomeRadiusFileName);
+ }
+ else if (StringEquals(filename.c_str(), "homey.g"))
+ {
+ filename.copy(HomeBedFileName);
+ }
}
+
return ret;
}
diff --git a/src/Movement/Kinematics/PolarKinematics.h b/src/Movement/Kinematics/PolarKinematics.h
index cb1a4c87..ae6199c3 100644
--- a/src/Movement/Kinematics/PolarKinematics.h
+++ b/src/Movement/Kinematics/PolarKinematics.h
@@ -27,7 +27,7 @@ public:
HomingMode GetHomingMode() const override { return homeIndividualMotors; }
AxesBitmap AxesAssumedHomed(AxesBitmap g92Axes) const override;
AxesBitmap MustBeHomedAxes(AxesBitmap axesMoving, bool disallowMovesBeforeHoming) const override;
- const char* GetHomingFileName(AxesBitmap toBeHomed, AxesBitmap alreadyHomed, size_t numVisibleAxes, AxesBitmap& mustHomeFirst) const override;
+ AxesBitmap GetHomingFileName(AxesBitmap toBeHomed, AxesBitmap alreadyHomed, size_t numVisibleAxes, const StringRef& filename) const override;
bool QueryTerminateHomingMove(size_t axis) const override;
void OnHomingSwitchTriggered(size_t axis, bool highEnd, const float stepsPerMm[], DDA& dda) const override;
void LimitSpeedAndAcceleration(DDA& dda, const float *normalisedDirectionVector) const override;
diff --git a/src/Movement/Kinematics/RotaryDeltaKinematics.cpp b/src/Movement/Kinematics/RotaryDeltaKinematics.cpp
index fd902353..d60aaf41 100644
--- a/src/Movement/Kinematics/RotaryDeltaKinematics.cpp
+++ b/src/Movement/Kinematics/RotaryDeltaKinematics.cpp
@@ -311,25 +311,16 @@ AxesBitmap RotaryDeltaKinematics::MustBeHomedAxes(AxesBitmap axesMoving, bool di
// This function is called when a request is made to home the axes in 'toBeHomed' and the axes in 'alreadyHomed' have already been homed.
// If we can proceed with homing some axes, return the name of the homing file to be called.
// If we can't proceed because other axes need to be homed first, return nullptr and pass those axes back in 'mustBeHomedFirst'.
-const char* RotaryDeltaKinematics::GetHomingFileName(AxesBitmap toBeHomed, AxesBitmap alreadyHomed, size_t numVisibleAxes, AxesBitmap& mustHomeFirst) const
+AxesBitmap RotaryDeltaKinematics::GetHomingFileName(AxesBitmap toBeHomed, AxesBitmap alreadyHomed, size_t numVisibleAxes, const StringRef& filename) const
{
// If homing X, Y or Z we must home all the towers
if ((toBeHomed & LowestNBits<AxesBitmap>(DELTA_AXES)) != 0)
{
- return "homedelta.g";
+ filename.copy("homedelta.g");
+ return 0;
}
- // Return the homing file for the lowest axis that we have been asked to home
- for (size_t axis = DELTA_AXES; axis < numVisibleAxes; ++axis)
- {
- if (IsBitSet(toBeHomed, axis))
- {
- return StandardHomingFileNames[axis];
- }
- }
-
- mustHomeFirst = 0;
- return nullptr;
+ return Kinematics::GetHomingFileName(toBeHomed, alreadyHomed, numVisibleAxes, filename);
}
// This function is called from the step ISR when an endstop switch is triggered during homing.
diff --git a/src/Movement/Kinematics/RotaryDeltaKinematics.h b/src/Movement/Kinematics/RotaryDeltaKinematics.h
index 0630e9f2..3b731820 100644
--- a/src/Movement/Kinematics/RotaryDeltaKinematics.h
+++ b/src/Movement/Kinematics/RotaryDeltaKinematics.h
@@ -33,7 +33,7 @@ public:
HomingMode GetHomingMode() const override { return homeIndividualMotors; }
AxesBitmap AxesAssumedHomed(AxesBitmap g92Axes) const override;
AxesBitmap MustBeHomedAxes(AxesBitmap axesMoving, bool disallowMovesBeforeHoming) const override;
- const char* GetHomingFileName(AxesBitmap toBeHomed, AxesBitmap alreadyHomed, size_t numVisibleAxes, AxesBitmap& mustHomeFirst) const override;
+ AxesBitmap GetHomingFileName(AxesBitmap toBeHomed, AxesBitmap alreadyHomed, size_t numVisibleAxes, const StringRef& filename) const override;
bool QueryTerminateHomingMove(size_t axis) const override;
void OnHomingSwitchTriggered(size_t axis, bool highEnd, const float stepsPerMm[], DDA& dda) const override;
bool WriteResumeSettings(FileStore *f) const override;
diff --git a/src/Movement/Kinematics/ScaraKinematics.cpp b/src/Movement/Kinematics/ScaraKinematics.cpp
index ff85c5e2..ac0bff98 100644
--- a/src/Movement/Kinematics/ScaraKinematics.cpp
+++ b/src/Movement/Kinematics/ScaraKinematics.cpp
@@ -345,7 +345,7 @@ size_t ScaraKinematics::NumHomingButtons(size_t numVisibleAxes) const
{
return 1;
}
- if (!storage->FileExists(SYS_DIR, StandardHomingFileNames[Z_AXIS]))
+ if (!storage->FileExists(SYS_DIR, "homez.g"))
{
return 2;
}
@@ -355,25 +355,29 @@ size_t ScaraKinematics::NumHomingButtons(size_t numVisibleAxes) const
// This function is called when a request is made to home the axes in 'toBeHomed' and the axes in 'alreadyHomed' have already been homed.
// If we can proceed with homing some axes, return the name of the homing file to be called.
// If we can't proceed because other axes need to be homed first, return nullptr and pass those axes back in 'mustBeHomedFirst'.
-const char* ScaraKinematics::GetHomingFileName(AxesBitmap toBeHomed, AxesBitmap alreadyHomed, size_t numVisibleAxes, AxesBitmap& mustHomeFirst) const
+AxesBitmap ScaraKinematics::GetHomingFileName(AxesBitmap toBeHomed, AxesBitmap alreadyHomed, size_t numVisibleAxes, const StringRef& filename) const
{
// Ask the base class which homing file we should call first
- const char* ret = Kinematics::GetHomingFileName(toBeHomed, alreadyHomed, numVisibleAxes, mustHomeFirst);
- // Change the returned name if it is X or Y
- if (ret == StandardHomingFileNames[X_AXIS])
- {
- ret = HomeProximalFileName;
- }
- else if (ret == StandardHomingFileNames[Y_AXIS])
- {
- ret = HomeDistalFileName;
- }
+ AxesBitmap ret = Kinematics::GetHomingFileName(toBeHomed, alreadyHomed, numVisibleAxes, filename);
- // Some SCARA printers cannot have individual axes homed safely. So it the user doesn't provide the homing file for an axis, default to homeall.
- const MassStorage *storage = reprap.GetPlatform().GetMassStorage();
- if (!storage->FileExists(SYS_DIR, ret))
+ if (ret == 0)
{
- ret = HomeAllFileName;
+ // Change the returned name if it is X or Y
+ if (StringEquals(filename.c_str(), "homex.g"))
+ {
+ filename.copy(HomeProximalFileName);
+ }
+ else if (StringEquals(filename.c_str(), "homey.g"))
+ {
+ filename.copy(HomeDistalFileName);
+ }
+
+ // Some SCARA printers cannot have individual axes homed safely. So it the user doesn't provide the homing file for an axis, default to homeall.
+ const MassStorage *storage = reprap.GetPlatform().GetMassStorage();
+ if (!storage->FileExists(SYS_DIR, filename.c_str()))
+ {
+ filename.copy(HomeAllFileName);
+ }
}
return ret;
}
diff --git a/src/Movement/Kinematics/ScaraKinematics.h b/src/Movement/Kinematics/ScaraKinematics.h
index 56506121..15913322 100644
--- a/src/Movement/Kinematics/ScaraKinematics.h
+++ b/src/Movement/Kinematics/ScaraKinematics.h
@@ -38,7 +38,7 @@ public:
HomingMode GetHomingMode() const override { return homeIndividualMotors; }
AxesBitmap AxesAssumedHomed(AxesBitmap g92Axes) const override;
AxesBitmap MustBeHomedAxes(AxesBitmap axesMoving, bool disallowMovesBeforeHoming) const override;
- const char* GetHomingFileName(AxesBitmap toBeHomed, AxesBitmap alreadyHomed, size_t numVisibleAxes, AxesBitmap& mustHomeFirst) const override;
+ AxesBitmap GetHomingFileName(AxesBitmap toBeHomed, AxesBitmap alreadyHomed, size_t numVisibleAxes, const StringRef& filename) const override;
bool QueryTerminateHomingMove(size_t axis) const override;
void OnHomingSwitchTriggered(size_t axis, bool highEnd, const float stepsPerMm[], DDA& dda) const override;
void LimitSpeedAndAcceleration(DDA& dda, const float *normalisedDirectionVector) const override;
diff --git a/src/Movement/Kinematics/ZLeadscrewKinematics.cpp b/src/Movement/Kinematics/ZLeadscrewKinematics.cpp
index ee7b5b96..89081f1a 100644
--- a/src/Movement/Kinematics/ZLeadscrewKinematics.cpp
+++ b/src/Movement/Kinematics/ZLeadscrewKinematics.cpp
@@ -92,7 +92,7 @@ bool ZLeadscrewKinematics::SupportsAutoCalibration() const
return numLeadscrews >= 2;
}
-// Perform auto calibration. Override this implementation in kinematics that support it. Caller already owns the GCode movement lock.
+// Perform auto calibration, returning true if failed. Override this implementation in kinematics that support it. Caller already owns the GCode movement lock.
bool ZLeadscrewKinematics::DoAutoCalibration(size_t numFactors, const RandomProbePointSet& probePoints, const StringRef& reply)
{
if (!SupportsAutoCalibration()) // should be checked by caller, but check it here too
@@ -274,11 +274,12 @@ bool ZLeadscrewKinematics::DoAutoCalibration(size_t numFactors, const RandomProb
}
}
+ bool failed = false;
if (haveNaN)
{
reply.printf("Calibration failed, computed corrections:");
AppendCorrections(solution, reply);
- return true;
+ failed = true;
}
else
{
@@ -289,7 +290,7 @@ bool ZLeadscrewKinematics::DoAutoCalibration(size_t numFactors, const RandomProb
{
reply.printf("Some computed corrections exceed configured limit of %.02fmm:", (double)maxCorrection);
AppendCorrections(solution, reply);
- return true;
+ failed = true;
}
else
{
@@ -298,7 +299,6 @@ bool ZLeadscrewKinematics::DoAutoCalibration(size_t numFactors, const RandomProb
AppendCorrections(solution, reply);
reply.catf(", points used %d, deviation before %.3f after %.3f",
numPoints, (double)sqrtf((float)initialSumOfSquares/numPoints), (double)sqrtf((float)sumOfSquares/numPoints));
- reprap.GetPlatform().MessageF(LogMessage, "%s\n", reply.c_str());
}
}
else
@@ -312,8 +312,9 @@ bool ZLeadscrewKinematics::DoAutoCalibration(size_t numFactors, const RandomProb
reply.catf(" %.2f turn %s (%.2fmm)", (double)(fabsf(netAdjustment)/screwPitch), (netAdjustment > 0) ? "down" : "up", (double)netAdjustment);
}
}
- return false;
}
+ reprap.GetPlatform().MessageF(LogMessage, "%s\n", reply.c_str());
+ return failed;
}
// Append the list of leadscrew corrections to 'reply'
diff --git a/src/Movement/Move.cpp b/src/Movement/Move.cpp
index 949d6398..9840f93c 100644
--- a/src/Movement/Move.cpp
+++ b/src/Movement/Move.cpp
@@ -46,6 +46,28 @@
constexpr uint32_t UsualMinimumPreparedTime = StepTimer::StepClockRate/10; // 100ms
constexpr uint32_t AbsoluteMinimumPreparedTime = StepTimer::StepClockRate/20; // 50ms
+#if SUPPORT_OBJECT_MODEL
+
+// Object model table and functions
+// Note: if using GCC version 7.3.1 20180622 and lambda functions are used in this table, you must compile this file with option -std=gnu++17.
+// Otherwise the table will be allocated in RAM instead of flash, which wastes too much RAM.
+
+// Macro to build a standard lambda function that includes the necessary type conversions
+#define OBJECT_MODEL_FUNC(_ret) OBJECT_MODEL_FUNC_BODY(Move, _ret)
+
+const ObjectModelTableEntry Move::objectModelTable[] =
+{
+ { "maxPrintingAcceleration", OBJECT_MODEL_FUNC(&(self->maxPrintingAcceleration)), TYPE_OF(float), ObjectModelTableEntry::none },
+ { "maxTravelAcceleration", OBJECT_MODEL_FUNC(&(self->maxTravelAcceleration)), TYPE_OF(float), ObjectModelTableEntry::none },
+ { "drcPeriod", OBJECT_MODEL_FUNC(&(self->drcPeriod)), TYPE_OF(float), ObjectModelTableEntry::none },
+ { "drcMinimumAcceleration", OBJECT_MODEL_FUNC(&(self->drcMinimumAcceleration)), TYPE_OF(float), ObjectModelTableEntry::none },
+ { "drcEnabled", OBJECT_MODEL_FUNC(&(self->drcEnabled)), TYPE_OF(bool), ObjectModelTableEntry::none },
+};
+
+DEFINE_GET_OBJECT_MODEL_TABLE(Move)
+
+#endif
+
Move::Move() : currentDda(nullptr), active(false), scheduledMoves(0), completedMoves(0)
{
kinematics = Kinematics::Create(KinematicsType::cartesian); // default to Cartesian
@@ -82,6 +104,7 @@ void Move::Init()
maxPrintingAcceleration = maxTravelAcceleration = 10000.0;
drcEnabled = false; // disable dynamic ringing cancellation
drcMinimumAcceleration = 10.0;
+ drcPeriod = 50.0;
// Clear the transforms
SetIdentityTransform();
diff --git a/src/Movement/Move.h b/src/Movement/Move.h
index a8fe46b2..68f1984b 100644
--- a/src/Movement/Move.h
+++ b/src/Movement/Move.h
@@ -37,7 +37,7 @@ constexpr uint32_t MovementStartDelayClocks = StepTimer::StepClockRate/100; //
// This is the master movement class. It controls all movement in the machine.
-class Move
+class Move INHERIT_OBJECT_MODEL
{
public:
Move();
@@ -129,9 +129,12 @@ public:
void ResetMoveCounters() { scheduledMoves = completedMoves = 0; }
HeightMap& AccessHeightMap() { return heightMap; } // Access the bed probing grid
+ const GridDefinition& GetGrid() const { return heightMap.GetGrid(); } // Get the grid definition
bool LoadHeightMapFromFile(FileStore *f, const StringRef& r); // Load the height map from a file returning true if an error occurred
bool SaveHeightMapToFile(FileStore *f) const; // Save the height map to a file returning true if an error occurred
+ const RandomProbePointSet& GetProbePoints() const { return probePoints; } // Return the probe point set constructed from G30 commands
+
const DDA *GetCurrentDDA() const { return currentDda; } // Return the DDA of the currently-executing move
float GetTopSpeed() const;
@@ -150,6 +153,9 @@ public:
static int32_t MotorEndPointToMachine(size_t drive, float coord); // Convert a single motor position to number of steps
static float MotorEndpointToPosition(int32_t endpoint, size_t drive); // Convert number of motor steps to motor position
+protected:
+ DECLARE_OBJECT_MODEL
+
private:
enum class MoveState : uint8_t
{
diff --git a/src/Movement/StepTimer.cpp b/src/Movement/StepTimer.cpp
index 16318305..35132656 100644
--- a/src/Movement/StepTimer.cpp
+++ b/src/Movement/StepTimer.cpp
@@ -31,7 +31,7 @@ namespace StepTimer
// 1.067us resolution on the Duet WiFi (120MHz clock)
// 0.853us resolution on the SAM E70 (150MHz clock)
- #if __LPC17xx__
+#if __LPC17xx__
//LPC has 32bit timers
//Using the same 128 divisor (as also specified in DDA)
//LPC Timers default to /4 --> (SystemCoreClock/4)
@@ -39,26 +39,25 @@ namespace StepTimer
//Start a free running Timer using Match Registers 0 and 1 to generate interrupts
LPC_SC->PCONP |= ((uint32_t) 1<<SBIT_PCTIM0); // Ensure the Power bit is set for the Timer
- STEP_TC->MCR = 0; //disable all MRx interrupts
+ STEP_TC->MCR = 0; // disable all MRx interrupts
STEP_TC->PR = (getPclk(PCLK_TIMER0) / res) - 1; // Set the LPC Prescaler (i.e. TC increment every 32 TimerClock Ticks)
STEP_TC->TC = 0x00; // Restart the Timer Count
NVIC_SetPriority(STEP_TC_IRQN, NvicPriorityStep); // set high priority for this IRQ; it's time-critical
NVIC_EnableIRQ(STEP_TC_IRQN);
STEP_TC->TCR = (1 <<SBIT_CNTEN); // Start Timer
- #else
+#else
pmc_set_writeprotect(false);
pmc_enable_periph_clk(STEP_TC_ID);
tc_init(STEP_TC, STEP_TC_CHAN, TC_CMR_WAVE | TC_CMR_WAVSEL_UP | TC_CMR_TCCLKS_TIMER_CLOCK4 | TC_CMR_EEVT_XC0); // must set TC_CMR_EEVT nonzero to get RB compare interrupts
STEP_TC->TC_CHANNEL[STEP_TC_CHAN].TC_IDR = ~(uint32_t)0; // interrupts disabled for now
- #if SAM4S || SAME70 // if 16-bit TCs
+#if SAM4S || SAME70 // if 16-bit TCs
STEP_TC->TC_CHANNEL[STEP_TC_CHAN].TC_IER = TC_IER_COVFS; // enable the overflow interrupt so that we can use it to extend the count to 32-bits
- #endif
+#endif
tc_start(STEP_TC, STEP_TC_CHAN);
tc_get_status(STEP_TC, STEP_TC_CHAN); // clear any pending interrupt
NVIC_SetPriority(STEP_TC_IRQN, NvicPriorityStep); // set priority for this IRQ
NVIC_EnableIRQ(STEP_TC_IRQN);
- #endif
-
+#endif
}
#if SAM4S || SAME70
@@ -93,22 +92,22 @@ namespace StepTimer
{
const irqflags_t flags = cpu_irq_save();
const int32_t diff = (int32_t)(tim - GetInterruptClocksInterruptsDisabled()); // see how long we have to go
- if (diff < (int32_t)DDA::MinInterruptInterval) // if less than about 6us or already passed
+ if (diff < (int32_t)DDA::MinInterruptInterval) // if less than about 6us or already passed
{
cpu_irq_restore(flags);
- return true; // tell the caller to simulate an interrupt instead
+ return true; // tell the caller to simulate an interrupt instead
}
#ifdef __LPC17xx__
STEP_TC->MR0 = tim;
- STEP_TC->MCR |= (1 << SBIT_MR0I); // Enable Int on MR0 match
+ STEP_TC->MCR |= (1 << SBIT_MR0I); // enable Int on MR0 match
#else
- STEP_TC->TC_CHANNEL[STEP_TC_CHAN].TC_RA = tim; // set up the compare register
+ STEP_TC->TC_CHANNEL[STEP_TC_CHAN].TC_RA = tim; // set up the compare register
// We would like to clear any pending step interrupt. To do this, we must read the TC status register.
// Unfortunately, this would clear any other pending interrupts from the same TC.
// So we don't, and the step ISR must allow for getting called prematurely.
- STEP_TC->TC_CHANNEL[STEP_TC_CHAN].TC_IER = TC_IER_CPAS; // enable the interrupt
+ STEP_TC->TC_CHANNEL[STEP_TC_CHAN].TC_IER = TC_IER_CPAS; // enable the interrupt
cpu_irq_restore(flags);
#endif
@@ -124,7 +123,7 @@ namespace StepTimer
void DisableStepInterrupt()
{
#ifdef __LPC17xx__
- STEP_TC->MCR &= ~(1<<SBIT_MR0I); //Disable Int on MR0
+ STEP_TC->MCR &= ~(1<<SBIT_MR0I); // disable Int on MR0
#else
STEP_TC->TC_CHANNEL[STEP_TC_CHAN].TC_IDR = TC_IER_CPAS;
# if SAM4S || SAME70
@@ -167,7 +166,7 @@ namespace StepTimer
void DisableSoftTimerInterrupt()
{
#ifdef __LPC17xx__
- STEP_TC->MCR &= ~(1<<SBIT_MR1I); //Disable Int on MR1
+ STEP_TC->MCR &= ~(1<<SBIT_MR1I); // disable Int on MR1
#else
STEP_TC->TC_CHANNEL[STEP_TC_CHAN].TC_IDR = TC_IER_CPBS;
# if SAM4S || SAME70
diff --git a/src/Movement/StepperDrivers/TMC22xx.cpp b/src/Movement/StepperDrivers/TMC22xx.cpp
index 6ed39636..03f0ebbe 100644
--- a/src/Movement/StepperDrivers/TMC22xx.cpp
+++ b/src/Movement/StepperDrivers/TMC22xx.cpp
@@ -138,7 +138,7 @@ constexpr uint32_t IHOLDIRUN_IHOLDDELAY_SHIFT = 16;
constexpr uint32_t IHOLDIRUN_IHOLDDELAY_MASK = 0x0F << IHOLDIRUN_IHOLDDELAY_SHIFT;
constexpr uint32_t DefaultIholdIrunReg = (0 << IHOLDIRUN_IHOLD_SHIFT) | (0 << IHOLDIRUN_IRUN_SHIFT) | (2 << IHOLDIRUN_IHOLDDELAY_SHIFT);
- // approx. 0.5 sec motor current reduction to half power
+ // approx. 0.5 sec motor current reduction to low power
constexpr uint8_t REGNUM_TPOWER_DOWN = 0x11;
constexpr uint8_t REGNUM_TSTEP = 0x12;
@@ -681,17 +681,20 @@ void TmcDriverState::Enable(bool en)
// Read the status
uint32_t TmcDriverState::ReadLiveStatus() const
{
- return readRegisters[ReadDrvStat] & (TMC_RR_OT | TMC_RR_OTPW | TMC_RR_S2G | TMC_RR_OLA | TMC_RR_OLB | TMC_RR_STST | TMC_RR_TEMPBITS);
+ const uint32_t ret = readRegisters[ReadDrvStat] & (TMC_RR_OT | TMC_RR_OTPW | TMC_RR_S2G | TMC_RR_OLA | TMC_RR_OLB | TMC_RR_STST | TMC_RR_TEMPBITS);
+ return (enabled) ? ret : ret & ~(TMC_RR_OLA | TMC_RR_OLB);
}
// Read the status
uint32_t TmcDriverState::ReadAccumulatedStatus(uint32_t bitsToKeep)
{
+ const uint32_t mask = (enabled) ? 0xFFFFFFFF : ~(TMC_RR_OLA | TMC_RR_OLB);
+ bitsToKeep &= mask;
const irqflags_t flags = cpu_irq_save();
const uint32_t status = accumulatedReadRegisters[ReadDrvStat];
accumulatedReadRegisters[ReadDrvStat] = (status & bitsToKeep) | readRegisters[ReadDrvStat]; // so that the next call to ReadAccumulatedStatus isn't missing some bits
cpu_irq_restore(flags);
- return status & (TMC_RR_OT | TMC_RR_OTPW | TMC_RR_S2G | TMC_RR_OLA | TMC_RR_OLB | TMC_RR_STST | TMC_RR_TEMPBITS);
+ return status & (TMC_RR_OT | TMC_RR_OTPW | TMC_RR_S2G | TMC_RR_OLA | TMC_RR_OLB | TMC_RR_STST | TMC_RR_TEMPBITS) & mask;
}
// Append the driver status to a string, and reset the min/max load values
diff --git a/src/Movement/StepperDrivers/TMC2660.cpp b/src/Movement/StepperDrivers/TMC2660.cpp
index dcb64247..240404d5 100644
--- a/src/Movement/StepperDrivers/TMC2660.cpp
+++ b/src/Movement/StepperDrivers/TMC2660.cpp
@@ -572,13 +572,13 @@ void TmcDriverState::UpdateChopConfRegister()
inline uint32_t TmcDriverState::ReadLiveStatus() const
{
const uint32_t ret = lastReadStatus & (TMC_RR_SG | TMC_RR_OT | TMC_RR_OTPW | TMC_RR_S2G | TMC_RR_OLA | TMC_RR_OLB | TMC_RR_STST);
- return (enabled) ? ret : ret & ~TMC_RR_SG;
+ return (enabled) ? ret : ret & ~(TMC_RR_SG | TMC_RR_OLA | TMC_RR_OLB);
}
// Read the status
uint32_t TmcDriverState::ReadAccumulatedStatus(uint32_t bitsToKeep)
{
- const uint32_t mask = (enabled) ? 0xFFFFFFFF : ~TMC_RR_SG;
+ const uint32_t mask = (enabled) ? 0xFFFFFFFF : ~(TMC_RR_SG | TMC_RR_OLA | TMC_RR_OLB);
bitsToKeep &= mask;
const irqflags_t flags = cpu_irq_save();
const uint32_t status = accumulatedStatus;
diff --git a/src/Networking/ESP8266WiFi/WiFiInterface.cpp b/src/Networking/ESP8266WiFi/WiFiInterface.cpp
index 718bcca2..3bbbcc33 100644
--- a/src/Networking/ESP8266WiFi/WiFiInterface.cpp
+++ b/src/Networking/ESP8266WiFi/WiFiInterface.cpp
@@ -156,6 +156,26 @@ WiFiInterface::WiFiInterface(Platform& p) : platform(p), uploader(nullptr), ftpD
strcpy(wiFiServerVersion, "(unknown)");
}
+#if SUPPORT_OBJECT_MODEL
+
+// Object model table and functions
+// Note: if using GCC version 7.3.1 20180622 and lambda functions are used in this table, you must compile this file with option -std=gnu++17.
+// Otherwise the table will be allocated in RAM instead of flash, which wastes too much RAM.
+
+// Macro to build a standard lambda function that includes the necessary type conversions
+#define OBJECT_MODEL_FUNC(_ret) OBJECT_MODEL_FUNC_BODY(WiFiInterface, _ret)
+
+const ObjectModelTableEntry WiFiInterface::objectModelTable[] =
+{
+ { "ip", OBJECT_MODEL_FUNC(&(self->ipAddress)), TYPE_OF(IPAddress), ObjectModelTableEntry::none },
+ { "netmask", OBJECT_MODEL_FUNC(&(self->netmask)), TYPE_OF(IPAddress), ObjectModelTableEntry::none },
+ { "gateway", OBJECT_MODEL_FUNC(&(self->gateway)), TYPE_OF(IPAddress), ObjectModelTableEntry::none }
+};
+
+DEFINE_GET_OBJECT_MODEL_TABLE(WiFiInterface)
+
+#endif
+
void WiFiInterface::Init()
{
interfaceMutex.Create("WiFi");
@@ -450,13 +470,9 @@ void WiFiInterface::Stop()
digitalWrite(EspResetPin, LOW); // put the ESP back into reset
DisableEspInterrupt(); // ignore IRQs from the transfer request pin
-#if SAME70
- NVIC_DisableIRQ(SPI0_IRQn);
- spi_disable(SPI0);
-#else
- NVIC_DisableIRQ(SPI_IRQn);
- spi_disable(SPI);
-#endif
+ NVIC_DisableIRQ(ESP_SPI_IRQn);
+ spi_disable(ESP_SPI);
+
spi_dma_check_rx_complete();
spi_dma_disable();
@@ -623,25 +639,26 @@ void WiFiInterface::Spin(bool full)
break;
case NetworkState::changingMode:
+ // Here when we have asked the ESP to change mode. Don't leave this state until we have a new status report from the ESP.
if (full && espStatusChanged && digitalRead(EspDataReadyPin))
{
GetNewStatus();
- if (currentMode != WiFiState::connecting)
+ switch (currentMode)
{
- requestedMode = currentMode; // don't keep repeating the request if it failed
+ case WiFiState::connecting:
+ case WiFiState::reconnecting:
+ case WiFiState::autoReconnecting:
+ break; // let the connect attempt continue
+
+ case WiFiState::connected:
+ case WiFiState::runningAsAccessPoint:
state = NetworkState::active;
- if (currentMode == WiFiState::connected || currentMode == WiFiState::runningAsAccessPoint)
{
// Get our IP address, this needs to be correct for FTP to work
Receiver<NetworkStatusResponse> status;
if (SendCommand(NetworkCommand::networkGetStatus, 0, 0, nullptr, 0, status) > 0)
{
- uint32_t ip = status.Value().ipAddress;
- for (size_t i = 0; i < 4; ++i)
- {
- ipAddress[i] = (uint8_t)(ip & 255);
- ip >>= 8;
- }
+ ipAddress.SetV4(status.Value().ipAddress);
SafeStrncpy(actualSsid, status.Value().ssid, SsidLength);
}
InitSockets();
@@ -651,10 +668,16 @@ void WiFiInterface::Spin(bool full)
actualSsid,
IP4String(ipAddress).c_str());
}
- else
+ break;
+
+ default:
+ if (requestedMode != WiFiState::connected)
{
- platform.MessageF(NetworkInfoMessage, "WiFi module is %s\n", TranslateWiFiState(currentMode));
+ requestedMode = currentMode; // don't keep repeating the request if it failed and it wasn't a connect request
}
+ state = NetworkState::active;
+ platform.MessageF(NetworkInfoMessage, "WiFi module is %s\n", TranslateWiFiState(currentMode));
+ break;
}
}
break;
@@ -878,11 +901,11 @@ void WiFiInterface::EspRequestsTransfer()
DisableEspInterrupt(); // don't allow more interrupts until we have acknowledged this one
}
-void WiFiInterface::SetIPAddress(const uint8_t p_ipAddress[], const uint8_t p_netmask[], const uint8_t p_gateway[])
+void WiFiInterface::SetIPAddress(IPAddress p_ip, IPAddress p_netmask, IPAddress p_gateway)
{
- memcpy(ipAddress, p_ipAddress, sizeof(ipAddress));
- memcpy(netmask, p_netmask, sizeof(netmask));
- memcpy(gateway, p_gateway, sizeof(gateway));
+ ipAddress = p_ip;
+ netmask = p_netmask;
+ gateway = p_gateway;
}
GCodeResult WiFiInterface::HandleWiFiCode(int mcode, GCodeBuffer &gb, const StringRef& reply, OutputBuffer*& longReply)
@@ -913,15 +936,21 @@ GCodeResult WiFiInterface::HandleWiFiCode(int mcode, GCodeBuffer &gb, const Stri
}
if (ok && gb.Seen('I'))
{
- gb.GetIPAddress(config.ip);
+ IPAddress temp;
+ gb.GetIPAddress(temp);
+ config.ip = temp.GetV4();
}
if (ok && gb.Seen('J'))
{
- ok = gb.GetIPAddress(config.gateway);
+ IPAddress temp;
+ ok = gb.GetIPAddress(temp);
+ config.gateway = temp.GetV4();
}
if (ok && gb.Seen('K'))
{
- ok = gb.GetIPAddress(config.netmask);
+ IPAddress temp;
+ ok = gb.GetIPAddress(temp);
+ config.netmask = temp.GetV4();
}
if (ok)
{
@@ -1044,7 +1073,9 @@ GCodeResult WiFiInterface::HandleWiFiCode(int mcode, GCodeBuffer &gb, const Stri
SafeStrncpy(config.password, password.c_str(), ARRAY_SIZE(config.password));
if (gb.Seen('I'))
{
- ok = gb.GetIPAddress(config.ip);
+ IPAddress temp;
+ ok = gb.GetIPAddress(temp);
+ config.ip = temp.GetV4();
config.channel = (gb.Seen('C')) ? gb.GetIValue() : 0;
}
else
diff --git a/src/Networking/ESP8266WiFi/WiFiInterface.h b/src/Networking/ESP8266WiFi/WiFiInterface.h
index 2dc85fe9..35435914 100644
--- a/src/Networking/ESP8266WiFi/WiFiInterface.h
+++ b/src/Networking/ESP8266WiFi/WiFiInterface.h
@@ -58,8 +58,8 @@ public:
bool IsWiFiInterface() const override { return true; }
void UpdateHostname(const char *hostname) override;
- const uint8_t *GetIPAddress() const override { return ipAddress; }
- void SetIPAddress(const uint8_t ipAddress[], const uint8_t netmask[], const uint8_t gateway[]) override;
+ IPAddress GetIPAddress() const override { return ipAddress; }
+ void SetIPAddress(IPAddress p_ip, IPAddress p_netmask, IPAddress p_gateway) override;
void SetMacAddress(const uint8_t mac[]) override;
const uint8_t *GetMacAddress() const override { return macAddress; }
@@ -79,6 +79,9 @@ public:
void EspRequestsTransfer();
void UpdateSocketStatus(uint16_t connectedSockets, uint16_t otherEndClosedSockets);
+protected:
+ DECLARE_OBJECT_MODEL
+
private:
enum class NetworkState
{
@@ -139,9 +142,9 @@ private:
bool activated;
volatile bool espStatusChanged;
- uint8_t ipAddress[4];
- uint8_t netmask[4];
- uint8_t gateway[4];
+ IPAddress ipAddress;
+ IPAddress netmask;
+ IPAddress gateway;
uint8_t macAddress[6];
char requestedSsid[SsidLength + 1];
char actualSsid[SsidLength + 1];
diff --git a/src/Networking/ESP8266WiFi/WiFiSocket.cpp b/src/Networking/ESP8266WiFi/WiFiSocket.cpp
index 6c7d51e9..fe22bd7b 100644
--- a/src/Networking/ESP8266WiFi/WiFiSocket.cpp
+++ b/src/Networking/ESP8266WiFi/WiFiSocket.cpp
@@ -170,7 +170,7 @@ void WiFiSocket::Poll(bool full)
}
localPort = resp.Value().localPort;
remotePort = resp.Value().remotePort;
- remoteIPAddress = resp.Value().remoteIp;
+ remoteIPAddress.SetV4(resp.Value().remoteIp);
DiscardReceivedData();
if (state != SocketState::waitingForResponder)
{
diff --git a/src/Networking/FtpResponder.cpp b/src/Networking/FtpResponder.cpp
index 0827b406..44b03690 100644
--- a/src/Networking/FtpResponder.cpp
+++ b/src/Networking/FtpResponder.cpp
@@ -551,9 +551,9 @@ void FtpResponder::ProcessLine()
}
// send FTP response
- const uint8_t * const ipAddress = skt->GetInterface()->GetIPAddress();
+ const IPAddress ipAddress = skt->GetInterface()->GetIPAddress();
outBuf->printf("227 Entering Passive Mode (%d,%d,%d,%d,%d,%d)\r\n",
- ipAddress[0], ipAddress[1], ipAddress[2], ipAddress[3],
+ ipAddress.GetQuad(0), ipAddress.GetQuad(1), ipAddress.GetQuad(2), ipAddress.GetQuad(3),
passivePort / 256, passivePort % 256);
Commit(ResponderState::waitingForPasvPort);
}
diff --git a/src/Networking/HttpResponder.cpp b/src/Networking/HttpResponder.cpp
index 3f241eb4..1bba4444 100644
--- a/src/Networking/HttpResponder.cpp
+++ b/src/Networking/HttpResponder.cpp
@@ -674,7 +674,7 @@ bool HttpResponder::Authenticate()
// Check and update the authentication
bool HttpResponder::CheckAuthenticated()
{
- const uint32_t remoteIP = GetRemoteIP();
+ const IPAddress remoteIP = GetRemoteIP();
for (size_t i = 0; i < numSessions; i++)
{
if (sessions[i].ip == remoteIP)
@@ -688,7 +688,7 @@ bool HttpResponder::CheckAuthenticated()
bool HttpResponder::RemoveAuthentication()
{
- const uint32_t remoteIP = skt->GetRemoteIP();
+ const IPAddress remoteIP = skt->GetRemoteIP();
for (size_t i = numSessions; i != 0; )
{
--i;
@@ -1155,7 +1155,7 @@ void HttpResponder::ProcessRequest()
uploadedBytes = 0;
// Keep track of the connection that is now uploading
- const uint32_t remoteIP = GetRemoteIP();
+ const IPAddress remoteIP = GetRemoteIP();
const uint16_t remotePort = skt->GetRemotePort();
for(size_t i = 0; i < numSessions; i++)
{
@@ -1238,7 +1238,7 @@ void HttpResponder::DoUpload()
if (uploadedBytes >= postFileLength)
{
// Reset POST upload state for this client
- const uint32_t remoteIP = GetRemoteIP();
+ const IPAddress remoteIP = GetRemoteIP();
for (size_t i = 0; i < numSessions; i++)
{
if (sessions[i].ip == remoteIP && sessions[i].isPostUploading)
diff --git a/src/Networking/HttpResponder.h b/src/Networking/HttpResponder.h
index ddc7e8fa..9f3d060e 100644
--- a/src/Networking/HttpResponder.h
+++ b/src/Networking/HttpResponder.h
@@ -65,7 +65,7 @@ private:
// HTTP sessions
struct HttpSession
{
- uint32_t ip;
+ IPAddress ip;
uint32_t lastQueryTime;
bool isPostUploading;
uint16_t postPort;
diff --git a/src/Networking/LwipEthernet/LwipEthernetInterface.cpp b/src/Networking/LwipEthernet/LwipEthernetInterface.cpp
index a3b08770..90b47523 100644
--- a/src/Networking/LwipEthernet/LwipEthernetInterface.cpp
+++ b/src/Networking/LwipEthernet/LwipEthernetInterface.cpp
@@ -138,6 +138,26 @@ LwipEthernetInterface::LwipEthernetInterface(Platform& p) : platform(p), closeDa
}
}
+#if SUPPORT_OBJECT_MODEL
+
+// Object model table and functions
+// Note: if using GCC version 7.3.1 20180622 and lambda functions are used in this table, you must compile this file with option -std=gnu++17.
+// Otherwise the table will be allocated in RAM instead of flash, which wastes too much RAM.
+
+// Macro to build a standard lambda function that includes the necessary type conversions
+#define OBJECT_MODEL_FUNC(_ret) OBJECT_MODEL_FUNC_BODY(LwipEthernetInterface, _ret)
+
+const ObjectModelTableEntry LwipEthernetInterface::objectModelTable[] =
+{
+ { "ip", OBJECT_MODEL_FUNC(&(self->ipAddress)), TYPE_OF(IPAddress), ObjectModelTableEntry::none },
+ { "netmask", OBJECT_MODEL_FUNC(&(self->netmask)), TYPE_OF(IPAddress), ObjectModelTableEntry::none },
+ { "gateway", OBJECT_MODEL_FUNC(&(self->gateway)), TYPE_OF(IPAddress), ObjectModelTableEntry::none }
+};
+
+DEFINE_GET_OBJECT_MODEL_TABLE(LwipEthernetInterface)
+
+#endif
+
void LwipEthernetInterface::Init()
{
interfaceMutex.Create("Lwip");
@@ -328,11 +348,10 @@ void LwipEthernetInterface::Exit()
// Get the network state into the reply buffer, returning true if there is some sort of error
GCodeResult LwipEthernetInterface::GetNetworkState(const StringRef& reply)
{
- const uint8_t * const config_ip = platform.GetIPAddress();
const int enableState = EnableState();
reply.printf("Ethernet is %s, configured IP address: %s, actual IP address: %s",
- (enableState == 0) ? "disabled" : "enabled",
- IP4String(config_ip).c_str(), IP4String(ethernet_get_ipaddress()).c_str());
+ (enableState == 0) ? "disabled" : "enabled",
+ IP4String(platform.GetIPAddress()).c_str(), IP4String(ethernet_get_ipaddress()).c_str());
return GCodeResult::ok;
}
@@ -350,7 +369,11 @@ void LwipEthernetInterface::Start()
// Allow the MAC address to be set only before LwIP is started...
ethernet_configure_interface(platform.GetDefaultMacAddress(), hostname);
- init_ethernet(DefaultIpAddress, DefaultNetMask, DefaultGateway);
+ uint8_t ipAddress[4], netmask[4], gateway[4];
+ DefaultIpAddress.UnpackV4(ipAddress);
+ DefaultNetMask.UnpackV4(netmask);
+ DefaultGateway.UnpackV4(gateway);
+ init_ethernet(ipAddress, netmask, gateway);
// Initialise mDNS subsystem
mdns_resp_init();
@@ -395,8 +418,7 @@ void LwipEthernetInterface::Spin(bool full)
case NetworkState::establishingLink:
if (ethernet_establish_link())
{
- const uint8_t *ipAddress = platform.GetIPAddress();
- usingDhcp = (ipAddress[0] == 0 && ipAddress[1] == 0 && ipAddress[2] == 0 && ipAddress[3] == 0);
+ usingDhcp = platform.GetIPAddress().IsNull();
if (usingDhcp)
{
// IP address is all zeros, so use DHCP
@@ -411,7 +433,11 @@ void LwipEthernetInterface::Spin(bool full)
// Using static IP address
state = NetworkState::connected;
// debugPrintf("Link established, network running\n");
- ethernet_set_configuration(platform.GetIPAddress(), platform.NetMask(), platform.GateWay());
+ uint8_t ipAddress[4], netmask[4], gateway[4];
+ platform.GetIPAddress().UnpackV4(ipAddress);
+ platform.NetMask().UnpackV4(netmask);
+ platform.GateWay().UnpackV4(gateway);
+ ethernet_set_configuration(ipAddress, netmask, gateway);
}
}
break;
@@ -567,16 +593,16 @@ bool LwipEthernetInterface::ConnectionEstablished(tcp_pcb *pcb)
return false;
}
-const uint8_t *LwipEthernetInterface::GetIPAddress() const
+IPAddress LwipEthernetInterface::GetIPAddress() const
{
- return ethernet_get_ipaddress();
+ return IPAddress(ethernet_get_ipaddress());
}
-void LwipEthernetInterface::SetIPAddress(const uint8_t ipAddress[], const uint8_t netmask[], const uint8_t gateway[])
+void LwipEthernetInterface::SetIPAddress(IPAddress p_ipAddress, IPAddress p_netmask, IPAddress p_gateway)
{
if (state == NetworkState::obtainingIP || state == NetworkState::active)
{
- const bool wantDhcp = (ipAddress[0] == 0 && ipAddress[1] == 0 && ipAddress[2] == 0 && ipAddress[3] == 0);
+ const bool wantDhcp = p_ipAddress.IsNull();
if (wantDhcp)
{
// Acquire dynamic IP address
@@ -602,6 +628,10 @@ void LwipEthernetInterface::SetIPAddress(const uint8_t ipAddress[], const uint8_
usingDhcp = false;
}
+ uint8_t ipAddress[4], netmask[4], gateway[4];
+ p_ipAddress.UnpackV4(ipAddress);
+ p_netmask.UnpackV4(netmask);
+ p_gateway.UnpackV4(gateway);
ethernet_set_configuration(ipAddress, netmask, gateway);
mdns_resp_netif_settings_changed(&gs_net_if);
}
diff --git a/src/Networking/LwipEthernet/LwipEthernetInterface.h b/src/Networking/LwipEthernet/LwipEthernetInterface.h
index 6acdfae1..974153a9 100644
--- a/src/Networking/LwipEthernet/LwipEthernetInterface.h
+++ b/src/Networking/LwipEthernet/LwipEthernetInterface.h
@@ -48,8 +48,8 @@ public:
bool IsWiFiInterface() const override { return false; }
void UpdateHostname(const char *hostname) override;
- const uint8_t *GetIPAddress() const override;
- void SetIPAddress(const uint8_t p_ipAddress[], const uint8_t p_netmask[], const uint8_t p_gateway[]) override;
+ IPAddress GetIPAddress() const override;
+ void SetIPAddress(IPAddress p_ipAddress, IPAddress p_netmask, IPAddress p_gateway) override;
void SetMacAddress(const uint8_t mac[]) override;
const uint8_t *GetMacAddress() const override { return macAddress; }
@@ -59,6 +59,9 @@ public:
void OpenDataPort(Port port) override;
void TerminateDataPort() override;
+protected:
+ DECLARE_OBJECT_MODEL
+
private:
enum class NetworkState
{
diff --git a/src/Networking/LwipEthernet/LwipSocket.cpp b/src/Networking/LwipEthernet/LwipSocket.cpp
index bfd244fc..7b236889 100644
--- a/src/Networking/LwipEthernet/LwipSocket.cpp
+++ b/src/Networking/LwipEthernet/LwipSocket.cpp
@@ -87,7 +87,7 @@ bool LwipSocket::AcceptConnection(tcp_pcb *pcb)
whenConnected = millis();
connectionPcb = pcb;
- remoteIPAddress = pcb->remote_ip.addr;
+ remoteIPAddress.SetV4(swap32(pcb->remote_ip.addr)); // LWIP IP addresses are big-endian, ours are little endian
remotePort = pcb->remote_port;
tcp_arg(pcb, this);
diff --git a/src/Networking/Network.cpp b/src/Networking/Network.cpp
index 47f9b1b8..6a69728c 100644
--- a/src/Networking/Network.cpp
+++ b/src/Networking/Network.cpp
@@ -54,6 +54,29 @@ Network::Network(Platform& p) : platform(p), responders(nullptr), nextResponderT
#endif
}
+#if SUPPORT_OBJECT_MODEL
+// Object model table and functions
+// Note: if using GCC version 7.3.1 20180622 and lambda functions are used in this table, you must compile this file with option -std=gnu++17.
+// Otherwise the table will be allocated in RAM instead of flash, which wastes too much RAM.
+
+static const ObjectModelArrayDescriptor interfaceArrayDescriptor =
+{
+ [] (ObjectModel *self) -> size_t { return NumNetworkInterfaces; },
+ [] (ObjectModel *self, size_t n) -> void* { return (void *)(((Network*)self)->GetInterface(n)); }
+};
+
+// Macro to build a standard lambda function that includes the necessary type conversions
+#define OBJECT_MODEL_FUNC(_ret) OBJECT_MODEL_FUNC_BODY(Network, _ret)
+
+const ObjectModelTableEntry Network::objectModelTable[] =
+{
+ { "interface", OBJECT_MODEL_FUNC_NOSELF(&interfaceArrayDescriptor), TYPE_OF(ObjectModel) | IsArray, ObjectModelTableEntry::none }
+};
+
+DEFINE_GET_OBJECT_MODEL_TABLE(Network)
+
+#endif
+
// Note that Platform::Init() must be called before this to that Platform::IsDuetWiFi() returns the correct value
void Network::Init()
{
@@ -358,22 +381,20 @@ int Network::EnableState(unsigned int interface) const
return -1;
}
-void Network::SetEthernetIPAddress(const uint8_t ipAddress[], const uint8_t netmask[], const uint8_t gateway[])
+void Network::SetEthernetIPAddress(IPAddress p_ipAddress, IPAddress p_netmask, IPAddress p_gateway)
{
for (NetworkInterface *iface : interfaces)
{
if (!iface->IsWiFiInterface())
{
- iface->SetIPAddress(ipAddress, netmask, gateway);
+ iface->SetIPAddress(p_ipAddress, p_netmask, p_gateway);
}
}
}
-const uint8_t *Network::GetIPAddress(unsigned int interface) const
+IPAddress Network::GetIPAddress(unsigned int interface) const
{
- static const uint8_t nullIpAddress[4] = { 0, 0, 0, 0 };
-
- return (interface < NumNetworkInterfaces) ? interfaces[interface]->GetIPAddress() : nullIpAddress;
+ return (interface < NumNetworkInterfaces) ? interfaces[interface]->GetIPAddress() : IPAddress();
}
void Network::SetHostname(const char *name)
diff --git a/src/Networking/Network.h b/src/Networking/Network.h
index 8d205e40..6e86a1b0 100644
--- a/src/Networking/Network.h
+++ b/src/Networking/Network.h
@@ -13,6 +13,7 @@
#include "MessageType.h"
#include "GCodes/GCodeResult.h"
#include "RTOSIface/RTOSIface.h"
+#include "ObjectModel/ObjectModel.h"
#if defined(DUET3) || defined(SAME70XPLD)
const size_t NumNetworkInterfaces = 2;
@@ -34,7 +35,7 @@ class WiFiInterface;
class WifiFirmwareUploader;
// The main network class that drives the network.
-class Network
+class Network INHERIT_OBJECT_MODEL
{
public:
Network(Platform& p);
@@ -63,8 +64,8 @@ public:
GCodeResult GetNetworkState(unsigned int interface, const StringRef& reply);
int EnableState(unsigned int interface) const;
- void SetEthernetIPAddress(const uint8_t p_ipAddress[], const uint8_t p_netmask[], const uint8_t p_gateway[]);
- const uint8_t *GetIPAddress(unsigned int interface) const;
+ void SetEthernetIPAddress(IPAddress p_ipAddress, IPAddress p_netmask, IPAddress p_gateway);
+ IPAddress GetIPAddress(unsigned int interface) const;
const char *GetHostname() const { return hostname; }
void SetHostname(const char *name);
void SetMacAddress(unsigned int interface, const uint8_t mac[]);
@@ -78,6 +79,13 @@ public:
void HandleTelnetGCodeReply(OutputBuffer *buf);
uint32_t GetHttpReplySeq();
+#if SUPPORT_OBJECT_MODEL
+ void *GetInterface(size_t n) { return interfaces[n]; }
+#endif
+
+protected:
+ DECLARE_OBJECT_MODEL
+
private:
WiFiInterface *FindWiFiInterface() const;
diff --git a/src/Networking/NetworkDefs.h b/src/Networking/NetworkDefs.h
index c72db43e..fb347d27 100644
--- a/src/Networking/NetworkDefs.h
+++ b/src/Networking/NetworkDefs.h
@@ -10,6 +10,7 @@
#include <cstdint>
#include <cstddef>
+#include <General/IPAddress.h>
class NetworkBuffer;
@@ -18,24 +19,24 @@ typedef uint8_t SocketNumber;
typedef uint16_t Port;
typedef uint8_t NetworkProtocol;
-const uint8_t DefaultMacAddress[6] = { 0xBE, 0xEF, 0xDE, 0xAD, 0xFE, 0xED };
+constexpr uint8_t DefaultMacAddress[6] = { 0xBE, 0xEF, 0xDE, 0xAD, 0xFE, 0xED };
-const uint8_t DefaultIpAddress[4] = { 0, 0, 0, 0 };
-const uint8_t DefaultNetMask[4] = { 255, 255, 255, 0 };
-const uint8_t DefaultGateway[4] = { 0, 0, 0, 0 };
+constexpr IPAddress DefaultIpAddress; // will be initialised to 0 by constructor
+const IPAddress DefaultNetMask((const uint8_t[]){ 255, 255, 255, 0 });
+constexpr IPAddress DefaultGateway; // will be initialised to 0 by constructor
-const size_t NumProtocols = 3; // number of network protocols we support, not counting FtpDataProtocol or AnyProtocol
-const NetworkProtocol HttpProtocol = 0, FtpProtocol = 1, TelnetProtocol = 2, FtpDataProtocol = 3, AnyProtocol = 255;
+constexpr size_t NumProtocols = 3; // number of network protocols we support, not counting FtpDataProtocol or AnyProtocol
+constexpr NetworkProtocol HttpProtocol = 0, FtpProtocol = 1, TelnetProtocol = 2, FtpDataProtocol = 3, AnyProtocol = 255;
-const size_t NumTcpPorts = NumProtocols + 1;
-const Port DefaultHttpPort = 80;
-const Port DefaultFtpPort = 21;
-const Port DefaultTelnetPort = 23;
+constexpr size_t NumTcpPorts = NumProtocols + 1;
+constexpr Port DefaultHttpPort = 80;
+constexpr Port DefaultFtpPort = 21;
+constexpr Port DefaultTelnetPort = 23;
-const Port DefaultPortNumbers[NumProtocols] = { DefaultHttpPort, DefaultFtpPort, DefaultTelnetPort };
-const char * const ProtocolNames[NumProtocols] = { "HTTP", "FTP", "TELNET" };
+constexpr Port DefaultPortNumbers[NumProtocols] = { DefaultHttpPort, DefaultFtpPort, DefaultTelnetPort };
+constexpr const char * ProtocolNames[NumProtocols] = { "HTTP", "FTP", "TELNET" };
-const size_t NetworkBufferCount = 6; // number of 2K network buffers
-const size_t SsidBufferLength = 32; // maximum characters in an SSID
+constexpr size_t NetworkBufferCount = 6; // number of 2K network buffers
+constexpr size_t SsidBufferLength = 32; // maximum characters in an SSID
#endif /* SRC_NETWORKING_NETWORKDEFS_H_ */
diff --git a/src/Networking/NetworkInterface.h b/src/Networking/NetworkInterface.h
index 4c807971..3aa4b068 100644
--- a/src/Networking/NetworkInterface.h
+++ b/src/Networking/NetworkInterface.h
@@ -11,7 +11,7 @@
#include "Network.h"
// Abstract base class for network modules
-class NetworkInterface
+class NetworkInterface INHERIT_OBJECT_MODEL
{
public:
virtual void Init() = 0;
@@ -31,8 +31,8 @@ public:
virtual GCodeResult DisableProtocol(NetworkProtocol protocol, const StringRef& reply) = 0;
virtual GCodeResult ReportProtocols(const StringRef& reply) const = 0;
- virtual const uint8_t *GetIPAddress() const = 0;
- virtual void SetIPAddress(const uint8_t p_ipAddress[], const uint8_t p_netmask[], const uint8_t p_gateway[]) = 0;
+ virtual IPAddress GetIPAddress() const = 0;
+ virtual void SetIPAddress(IPAddress p_ipAddress, IPAddress p_netmask, IPAddress p_gateway) = 0;
virtual void SetMacAddress(const uint8_t mac[]) = 0;
virtual const uint8_t *GetMacAddress() const = 0;
diff --git a/src/Networking/NetworkResponder.cpp b/src/Networking/NetworkResponder.cpp
index 00614cd0..85b0ccaa 100644
--- a/src/Networking/NetworkResponder.cpp
+++ b/src/Networking/NetworkResponder.cpp
@@ -235,9 +235,9 @@ void NetworkResponder::FinishUpload(uint32_t fileLength, time_t fileLastModified
filenameBeingUploaded[0] = 0;
}
-uint32_t NetworkResponder::GetRemoteIP() const
+IPAddress NetworkResponder::GetRemoteIP() const
{
- return (skt == nullptr) ? 0 : skt->GetRemoteIP();
+ return (skt == nullptr) ? IPAddress() : skt->GetRemoteIP();
}
void NetworkResponder::ReportOutputBufferExhaustion(const char *sourceFile, int line)
diff --git a/src/Networking/NetworkResponder.h b/src/Networking/NetworkResponder.h
index 076988a9..98a9e775 100644
--- a/src/Networking/NetworkResponder.h
+++ b/src/Networking/NetworkResponder.h
@@ -63,7 +63,7 @@ protected:
void FinishUpload(uint32_t fileLength, time_t fileLastModified);
virtual void CancelUpload();
- uint32_t GetRemoteIP() const;
+ IPAddress GetRemoteIP() const;
void ReportOutputBufferExhaustion(const char *sourceFile, int line);
static Platform& GetPlatform() { return reprap.GetPlatform(); }
diff --git a/src/Networking/Socket.h b/src/Networking/Socket.h
index d7525e8e..5a0b22ce 100644
--- a/src/Networking/Socket.h
+++ b/src/Networking/Socket.h
@@ -9,6 +9,7 @@
#define SRC_NETWORKING_SOCKET_H_
#include "NetworkDefs.h"
+#include "General/IPAddress.h"
const uint32_t FindResponderTimeout = 2000; // how long we wait for a responder to become available
const uint32_t MaxAckTime = 4000; // how long we wait for a connection to acknowledge the remaining data before it is closed
@@ -21,11 +22,11 @@ class NetworkInterface;
class Socket
{
public:
- Socket(NetworkInterface *iface) : interface(iface), localPort(0), remotePort(0), remoteIPAddress(0), state(SocketState::disabled) { }
+ Socket(NetworkInterface *iface) : interface(iface), localPort(0), remotePort(0), remoteIPAddress(), state(SocketState::disabled) { }
NetworkInterface *GetInterface() const { return interface; }
Port GetLocalPort() const { return localPort; }
- uint32_t GetRemoteIP() const { return remoteIPAddress; }
+ IPAddress GetRemoteIP() const { return remoteIPAddress; }
Port GetRemotePort() const { return remotePort; }
NetworkProtocol GetProtocol() const { return protocol; }
@@ -56,7 +57,7 @@ protected:
NetworkInterface * const interface;
Port localPort, remotePort; // The local and remote ports
NetworkProtocol protocol; // What protocol this socket is for
- uint32_t remoteIPAddress; // The remote IP address
+ IPAddress remoteIPAddress; // The remote IP address
SocketState state;
};
diff --git a/src/Networking/W5500Ethernet/W5500Interface.cpp b/src/Networking/W5500Ethernet/W5500Interface.cpp
index 630d7c36..89fc3d84 100644
--- a/src/Networking/W5500Ethernet/W5500Interface.cpp
+++ b/src/Networking/W5500Ethernet/W5500Interface.cpp
@@ -33,6 +33,26 @@ W5500Interface::W5500Interface(Platform& p)
}
}
+#if SUPPORT_OBJECT_MODEL
+
+// Object model table and functions
+// Note: if using GCC version 7.3.1 20180622 and lambda functions are used in this table, you must compile this file with option -std=gnu++17.
+// Otherwise the table will be allocated in RAM instead of flash, which wastes too much RAM.
+
+// Macro to build a standard lambda function that includes the necessary type conversions
+#define OBJECT_MODEL_FUNC(_ret) OBJECT_MODEL_FUNC_BODY(W5500Interface, _ret)
+
+const ObjectModelTableEntry W5500Interface::objectModelTable[] =
+{
+ { "ip", OBJECT_MODEL_FUNC(&(self->ipAddress)), TYPE_OF(IPAddress), ObjectModelTableEntry::none },
+ { "netmask", OBJECT_MODEL_FUNC(&(self->netmask)), TYPE_OF(IPAddress), ObjectModelTableEntry::none },
+ { "gateway", OBJECT_MODEL_FUNC(&(self->gateway)), TYPE_OF(IPAddress), ObjectModelTableEntry::none }
+};
+
+DEFINE_GET_OBJECT_MODEL_TABLE(W5500Interface)
+
+#endif
+
void W5500Interface::Init()
{
interfaceMutex.Create("W5500");
@@ -212,7 +232,7 @@ void W5500Interface::Exit()
// Get the network state into the reply buffer, returning true if there is some sort of error
GCodeResult W5500Interface::GetNetworkState(const StringRef& reply)
{
- const uint8_t * const config_ip = platform.GetIPAddress();
+ const IPAddress config_ip = platform.GetIPAddress();
const int enableState = EnableState();
reply.printf("Network is %s, configured IP address: %s, actual IP address: %s",
(enableState == 0) ? "disabled" : "enabled",
@@ -292,7 +312,7 @@ void W5500Interface::Spin(bool full)
if (full && wizphy_getphylink() == PHY_LINK_ON)
{
- usingDhcp = (ipAddress[0] == 0 && ipAddress[1] == 0 && ipAddress[2] == 0 && ipAddress[3] == 0);
+ usingDhcp = (ipAddress.GetV4() == 0);
if (usingDhcp)
{
// IP address is all zeros, so use DHCP
@@ -443,11 +463,11 @@ int W5500Interface::EnableState() const
return (state == NetworkState::disabled) ? 0 : 1;
}
-void W5500Interface::SetIPAddress(const uint8_t p_ipAddress[], const uint8_t p_netmask[], const uint8_t p_gateway[])
+void W5500Interface::SetIPAddress(IPAddress p_ipAddress, IPAddress p_netmask, IPAddress p_gateway)
{
- memcpy(ipAddress, p_ipAddress, sizeof(ipAddress));
- memcpy(netmask, p_netmask, sizeof(netmask));
- memcpy(gateway, p_gateway, sizeof(gateway));
+ ipAddress = p_ipAddress;
+ netmask = p_netmask;
+ gateway = p_gateway;
}
void W5500Interface::OpenDataPort(Port port)
diff --git a/src/Networking/W5500Ethernet/W5500Interface.h b/src/Networking/W5500Ethernet/W5500Interface.h
index 3f20b7ab..5a2b6f10 100644
--- a/src/Networking/W5500Ethernet/W5500Interface.h
+++ b/src/Networking/W5500Ethernet/W5500Interface.h
@@ -52,13 +52,17 @@ public:
bool IsWiFiInterface() const override { return false; }
void UpdateHostname(const char *name) override { }
- const uint8_t *GetIPAddress() const override { return ipAddress; }
+ IPAddress GetIPAddress() const override { return ipAddress; }
+ void SetIPAddress(IPAddress p_ipAddress, IPAddress p_netmask, IPAddress p_gateway) override;
void SetMacAddress(const uint8_t mac[]) override;
const uint8_t *GetMacAddress() const override { return macAddress; }
void OpenDataPort(Port port) override;
void TerminateDataPort() override;
+protected:
+ DECLARE_OBJECT_MODEL
+
private:
enum class NetworkState
{
@@ -84,7 +88,6 @@ private:
void ReportOneProtocol(NetworkProtocol protocol, const StringRef& reply) const
pre(protocol < NumProtocols);
- void SetIPAddress(const uint8_t p_ipAddress[], const uint8_t p_netmask[], const uint8_t p_gateway[]);
Platform& platform;
uint32_t lastTickMillis;
@@ -98,9 +101,9 @@ private:
bool activated;
bool usingDhcp;
- uint8_t ipAddress[4];
- uint8_t netmask[4];
- uint8_t gateway[4];
+ IPAddress ipAddress;
+ IPAddress netmask;
+ IPAddress gateway;
uint8_t macAddress[6];
};
diff --git a/src/Networking/W5500Ethernet/W5500Socket.cpp b/src/Networking/W5500Ethernet/W5500Socket.cpp
index f6bacc2b..f95b6930 100644
--- a/src/Networking/W5500Ethernet/W5500Socket.cpp
+++ b/src/Networking/W5500Ethernet/W5500Socket.cpp
@@ -171,7 +171,7 @@ void W5500Socket::Poll(bool full)
if (getSn_IR(socketNum) & Sn_IR_CON)
{
// New connection, so retrieve the sending IP address and port, and clear the interrupt
- getSn_DIPR(socketNum, reinterpret_cast<uint8_t*>(&remoteIPAddress));
+ getSn_DIPR(socketNum, remoteIPAddress);
remotePort = getSn_DPORT(socketNum);
setSn_IR(socketNum, Sn_IR_CON);
whenConnected = millis();
diff --git a/src/Networking/W5500Ethernet/Wiznet/Ethernet/W5500/w5500.cpp b/src/Networking/W5500Ethernet/Wiznet/Ethernet/W5500/w5500.cpp
index 364133f5..d4dafbd7 100644
--- a/src/Networking/W5500Ethernet/Wiznet/Ethernet/W5500/w5500.cpp
+++ b/src/Networking/W5500Ethernet/Wiznet/Ethernet/W5500/w5500.cpp
@@ -95,6 +95,21 @@ void WIZCHIP_WRITE_BUF(uint32_t AddrSel, const uint8_t* pBuf, uint16_t len)
WizSpi::ReleaseSS();
}
+// Read into an IPAddress
+void WIZCHIP_READ_IP(uint32_t AddrSel, IPAddress& ip)
+{
+ uint8_t ipBuf[4];
+ WIZCHIP_READ_BUF(AddrSel, ipBuf, 4);
+ ip.SetV4(ipBuf);
+}
+
+// Write to an IPAddress
+void WIZCHIP_WRITE_IP(uint32_t AddrSel, const IPAddress& ip)
+{
+ uint8_t ipBuf[4];
+ ip.UnpackV4(ipBuf);
+ WIZCHIP_WRITE_BUF(AddrSel, ipBuf, 4);
+}
uint16_t getSn_TX_FSR(uint8_t sn)
{
diff --git a/src/Networking/W5500Ethernet/Wiznet/Ethernet/W5500/w5500.h b/src/Networking/W5500Ethernet/Wiznet/Ethernet/W5500/w5500.h
index e14c71ab..ad585aa9 100644
--- a/src/Networking/W5500Ethernet/Wiznet/Ethernet/W5500/w5500.h
+++ b/src/Networking/W5500Ethernet/Wiznet/Ethernet/W5500/w5500.h
@@ -52,6 +52,7 @@
#include <cstdint>
#include <cstddef>
#include "spi/spi.h"
+#include <General/IPAddress.h>
// The following functions are defined in Network.cpp and used by this module
extern void SpiAssertSS();
@@ -1301,6 +1302,12 @@ void WIZCHIP_READ_BUF (uint32_t AddrSel, uint8_t* pBuf, uint16_t len);
*/
void WIZCHIP_WRITE_BUF(uint32_t AddrSel, const uint8_t* pBuf, uint16_t len);
+// Read into an IPAddress
+void WIZCHIP_READ_IP(uint32_t AddrSel, IPAddress& ip);
+
+// Write to an IPAddress
+void WIZCHIP_WRITE_IP(uint32_t AddrSel, const IPAddress& ip);
+
/////////////////////////////////
// Common Register I/O function //
/////////////////////////////////
@@ -1333,9 +1340,9 @@ static inline uint8_t getMR()
* @param (uint8_t*)gar Pointer variable to set gateway IP address. It should be allocated 4 bytes.
* @sa getGAR()
*/
-static inline void setGAR(const uint8_t *gar)
+static inline void setGAR(const IPAddress& gar)
{
- WIZCHIP_WRITE_BUF(GAR, gar, 4);
+ WIZCHIP_WRITE_IP(GAR, gar);
}
/**
@@ -1344,9 +1351,9 @@ static inline void setGAR(const uint8_t *gar)
* @param (uint8_t*)gar Pointer variable to get gateway IP address. It should be allocated 4 bytes.
* @sa setGAR()
*/
-static inline void getGAR(uint8_t *gar)
+static inline void getGAR(IPAddress& gar)
{
- WIZCHIP_READ_BUF(GAR, gar, 4);
+ WIZCHIP_READ_IP(GAR, gar);
}
/**
@@ -1355,21 +1362,20 @@ static inline void getGAR(uint8_t *gar)
* @param (uint8_t*)subr Pointer variable to set subnet mask address. It should be allocated 4 bytes.
* @sa getSUBR()
*/
-static inline void setSUBR(const uint8_t *subr)
+static inline void setSUBR(const IPAddress& subr)
{
- WIZCHIP_WRITE_BUF(SUBR, subr, 4);
+ WIZCHIP_WRITE_IP(SUBR, subr);
}
-
/**
* @ingroup Common_register_access_function
* @brief Get subnet mask address
* @param (uint8_t*)subr Pointer variable to get subnet mask address. It should be allocated 4 bytes.
* @sa setSUBR()
*/
-static inline void getSUBR(uint8_t* subr)
+static inline void getSUBR(IPAddress& subr)
{
- WIZCHIP_READ_BUF(SUBR, subr, 4);
+ WIZCHIP_READ_IP(SUBR, subr);
}
/**
@@ -1400,9 +1406,9 @@ static inline void getSHAR(uint8_t *shar)
* @param (uint8_t*)sipr Pointer variable to set local IP address. It should be allocated 4 bytes.
* @sa getSIPR()
*/
-static inline void setSIPR(const uint8_t *sipr)
+static inline void setSIPR(const IPAddress& sipr)
{
- WIZCHIP_WRITE_BUF(SIPR, sipr, 4);
+ WIZCHIP_WRITE_IP(SIPR, sipr);
}
/**
@@ -1411,9 +1417,9 @@ static inline void setSIPR(const uint8_t *sipr)
* @param (uint8_t*)sipr Pointer variable to get local IP address. It should be allocated 4 bytes.
* @sa setSIPR()
*/
-static inline void getSIPR(uint8_t *sipr)
+static inline void getSIPR(IPAddress& sipr)
{
- WIZCHIP_READ_BUF(SIPR, sipr, 4);
+ WIZCHIP_READ_IP(SIPR, sipr);
}
/**
@@ -1913,9 +1919,9 @@ static inline void getSn_DHAR(uint8_t sn, uint8_t *dhar)
* @param (uint8_t*)dipr Pointer variable to set socket n destination IP address. It should be allocated 4 bytes.
* @sa getSn_DIPR()
*/
-static inline void setSn_DIPR(uint8_t sn, const uint8_t *dipr)
+static inline void setSn_DIPR(uint8_t sn, const IPAddress& dipr)
{
- WIZCHIP_WRITE_BUF(Sn_DIPR(sn), dipr, 4);
+ WIZCHIP_WRITE_IP(Sn_DIPR(sn), dipr);
}
/**
@@ -1925,9 +1931,9 @@ static inline void setSn_DIPR(uint8_t sn, const uint8_t *dipr)
* @param (uint8_t*)dipr Pointer variable to get socket n destination IP address. It should be allocated 4 bytes.
* @sa setSn_DIPR()
*/
-static inline void getSn_DIPR(uint8_t sn, uint8_t *dipr)
+static inline void getSn_DIPR(uint8_t sn, IPAddress& dipr)
{
- WIZCHIP_READ_BUF(Sn_DIPR(sn), dipr, 4);
+ WIZCHIP_READ_IP(Sn_DIPR(sn), dipr);
}
/**
diff --git a/src/Networking/W5500Ethernet/Wiznet/Ethernet/socketlib.cpp b/src/Networking/W5500Ethernet/Wiznet/Ethernet/socketlib.cpp
index 01320fa8..43a82fc8 100644
--- a/src/Networking/W5500Ethernet/Wiznet/Ethernet/socketlib.cpp
+++ b/src/Networking/W5500Ethernet/Wiznet/Ethernet/socketlib.cpp
@@ -107,9 +107,9 @@ int8_t socket(uint8_t sn, uint8_t protocol, uint16_t port, uint8_t flag)
{
case Sn_MR_TCP:
{
- uint32_t taddr;
- getSIPR((uint8_t*)&taddr);
- if (taddr == 0)
+ IPAddress taddr;
+ getSIPR(taddr);
+ if (taddr.GetV4() == 0)
{
return SOCKERR_SOCKINIT;
}
@@ -210,27 +210,21 @@ int8_t listen(uint8_t sn)
return SOCK_OK;
}
-int8_t connect(uint8_t sn, uint8_t * addr, uint16_t port)
+int8_t connect(uint8_t sn, IPAddress addr, uint16_t port)
{
CHECK_SOCKMODE(Sn_MR_TCP);
CHECK_SOCKINIT();
+ if (addr.IsNull() || addr.IsBroadcast() == 0)
{
- uint32_t taddr = ((uint32_t)addr[0] & 0x000000FF);
- taddr = (taddr << 8) + ((uint32_t)addr[1] & 0x000000FF);
- taddr = (taddr << 8) + ((uint32_t)addr[2] & 0x000000FF);
- taddr = (taddr << 8) + ((uint32_t)addr[3] & 0x000000FF);
- if (taddr == 0xFFFFFFFF || taddr == 0)
- {
- return SOCKERR_IPINVALID;
- }
+ return SOCKERR_IPINVALID;
}
if (port == 0)
{
return SOCKERR_PORTZERO;
}
- setSn_DIPR(sn,addr);
- setSn_DPORT(sn,port);
+ setSn_DIPR(sn, addr);
+ setSn_DPORT(sn, port);
ExecCommand(sn, Sn_CR_CONNECT);
if (sock_io_mode & (1<<sn))
{
@@ -258,7 +252,7 @@ void disconnectNoWait(uint8_t sn)
ExecCommand(sn, Sn_CR_DISCON);
}
-int32_t sendto(uint8_t sn, const uint8_t * buf, uint16_t len, const uint8_t * addr, uint16_t port)
+int32_t sendto(uint8_t sn, const uint8_t * buf, uint16_t len, IPAddress destIp, uint16_t port)
{
switch(getSn_MR(sn) & 0x0F)
{
@@ -270,11 +264,7 @@ int32_t sendto(uint8_t sn, const uint8_t * buf, uint16_t len, const uint8_t * ad
}
CHECK_SOCKDATA();
- uint32_t taddr = ((uint32_t)addr[0]) & 0x000000FF;
- taddr = (taddr << 8) + ((uint32_t)addr[1] & 0x000000FF);
- taddr = (taddr << 8) + ((uint32_t)addr[2] & 0x000000FF);
- taddr = (taddr << 8) + ((uint32_t)addr[3] & 0x000000FF);
- if (taddr == 0)
+ if (destIp.GetV4() == 0)
{
return SOCKERR_IPINVALID;
}
@@ -288,8 +278,8 @@ int32_t sendto(uint8_t sn, const uint8_t * buf, uint16_t len, const uint8_t * ad
return SOCKERR_SOCKSTATUS;
}
- setSn_DIPR(sn,addr);
- setSn_DPORT(sn,port);
+ setSn_DIPR(sn, destIp);
+ setSn_DPORT(sn, port);
uint16_t freesize = getSn_TxMAX(sn);
if (len > freesize)
{
@@ -518,7 +508,10 @@ int8_t setsockopt(uint8_t sn, sockopt_type sotype, void* arg)
setSn_MSSR(sn,*(uint16_t*)arg);
break;
case SO_DESTIP:
- setSn_DIPR(sn, (uint8_t*)arg);
+ {
+ IPAddress ip((uint8_t*)arg);
+ setSn_DIPR(sn, ip);
+ }
break;
case SO_DESTPORT:
setSn_DPORT(sn, *(uint16_t*)arg);
@@ -566,7 +559,11 @@ int8_t getsockopt(uint8_t sn, sockopt_type sotype, void* arg)
*(uint8_t*) arg = getSn_MSSR(sn);
break;
case SO_DESTIP:
- getSn_DIPR(sn, (uint8_t*)arg);
+ {
+ IPAddress ip;
+ getSn_DIPR(sn, ip);
+ ip.UnpackV4((uint8_t*)arg);
+ }
break;
case SO_DESTPORT:
*(uint16_t*) arg = getSn_DPORT(sn);
diff --git a/src/Networking/W5500Ethernet/Wiznet/Ethernet/socketlib.h b/src/Networking/W5500Ethernet/Wiznet/Ethernet/socketlib.h
index 167711de..eb2990c6 100644
--- a/src/Networking/W5500Ethernet/Wiznet/Ethernet/socketlib.h
+++ b/src/Networking/W5500Ethernet/Wiznet/Ethernet/socketlib.h
@@ -207,7 +207,7 @@ int8_t listen(uint8_t sn);
* @ref SOCKERR_TIMEOUT - Timeout occurred during request connection\n
* @ref SOCK_BUSY - In non-block io mode, it returned immediately\n
*/
-int8_t connect(uint8_t sn, uint8_t * addr, uint16_t port);
+int8_t connect(uint8_t sn, IPAddress addr, uint16_t port);
void disconnectNoWait(uint8_t sn);
@@ -236,7 +236,7 @@ void disconnectNoWait(uint8_t sn);
* @ref SOCKERR_TIMEOUT - Timeout occurred \n
* @ref SOCK_BUSY - Socket is busy.
*/
-int32_t sendto(uint8_t sn, const uint8_t * buf, uint16_t len, const uint8_t * addr, uint16_t port);
+int32_t sendto(uint8_t sn, const uint8_t * buf, uint16_t len, IPAddress destIp, uint16_t port);
/**
* @ingroup WIZnet_socket_APIs
diff --git a/src/Networking/W5500Ethernet/Wiznet/Ethernet/wizchip_conf.cpp b/src/Networking/W5500Ethernet/Wiznet/Ethernet/wizchip_conf.cpp
index dc42002c..ebd1accc 100644
--- a/src/Networking/W5500Ethernet/Wiznet/Ethernet/wizchip_conf.cpp
+++ b/src/Networking/W5500Ethernet/Wiznet/Ethernet/wizchip_conf.cpp
@@ -59,8 +59,6 @@
* @\ref WIZCHIP instance data
*/
-static uint8_t _DNS_[4]; // DNS server ip address
-static dhcp_mode _DHCP_; // DHCP mode
static const char WizchipId[6] = "w5500";
int8_t ctlwizchip(ctlwizchip_type cwtype, void* arg)
@@ -140,37 +138,9 @@ int8_t ctlwizchip(ctlwizchip_type cwtype, void* arg)
return 0;
}
-
-int8_t ctlnetwork(ctlnetwork_type cntype, void* arg)
-{
- switch(cntype)
- {
- case CN_SET_NETINFO:
- wizchip_setnetinfo((wiz_NetInfo*)arg);
- break;
- case CN_GET_NETINFO:
- wizchip_getnetinfo((wiz_NetInfo*)arg);
- break;
- case CN_SET_NETMODE:
- return wizchip_setnetmode(*(netmode_type*)arg);
- case CN_GET_NETMODE:
- *(netmode_type*)arg = wizchip_getnetmode();
- break;
- case CN_SET_TIMEOUT:
- wizchip_settimeout((wiz_NetTimeout*)arg);
- break;
- case CN_GET_TIMEOUT:
- wizchip_gettimeout((wiz_NetTimeout*)arg);
- break;
- default:
- return -1;
- }
- return 0;
-}
-
void wizchip_sw_reset(void)
{
- uint8_t gw[4], sn[4], sip[4];
+ IPAddress gw, sn, sip;
uint8_t mac[6];
getSHAR(mac);
getGAR(gw); getSUBR(sn); getSIPR(sip);
@@ -398,33 +368,6 @@ int8_t wizphy_setphypmode(uint8_t pmode)
return -1;
}
-
-void wizchip_setnetinfo(wiz_NetInfo* pnetinfo)
-{
- setSHAR(pnetinfo->mac);
- setGAR(pnetinfo->gw);
- setSUBR(pnetinfo->sn);
- setSIPR(pnetinfo->ip);
- _DNS_[0] = pnetinfo->dns[0];
- _DNS_[1] = pnetinfo->dns[1];
- _DNS_[2] = pnetinfo->dns[2];
- _DNS_[3] = pnetinfo->dns[3];
- _DHCP_ = pnetinfo->dhcp;
-}
-
-void wizchip_getnetinfo(wiz_NetInfo* pnetinfo)
-{
- getSHAR(pnetinfo->mac);
- getGAR(pnetinfo->gw);
- getSUBR(pnetinfo->sn);
- getSIPR(pnetinfo->ip);
- pnetinfo->dns[0]= _DNS_[0];
- pnetinfo->dns[1]= _DNS_[1];
- pnetinfo->dns[2]= _DNS_[2];
- pnetinfo->dns[3]= _DNS_[3];
- pnetinfo->dhcp = _DHCP_;
-}
-
int8_t wizchip_setnetmode(netmode_type netmode)
{
if (netmode & ~(NM_WAKEONLAN | NM_PPPOE | NM_PINGBLOCK | NM_FORCEARP))
diff --git a/src/Networking/W5500Ethernet/Wiznet/Ethernet/wizchip_conf.h b/src/Networking/W5500Ethernet/Wiznet/Ethernet/wizchip_conf.h
index ceeec9a6..ddf5688c 100644
--- a/src/Networking/W5500Ethernet/Wiznet/Ethernet/wizchip_conf.h
+++ b/src/Networking/W5500Ethernet/Wiznet/Ethernet/wizchip_conf.h
@@ -284,18 +284,6 @@ struct wiz_NetTimeout
*/
int8_t ctlwizchip(ctlwizchip_type cwtype, void* arg);
-/**
- * @ingroup extra_functions
- * @brief Controls to network.
- * @details Controls to network environment, mode, timeout and so on.
- * @param cntype : Input. Decides to the control type
- * @param arg : Inout. arg type is dependent on cntype.
- * @return -1 : Fail because of invalid \ref ctlnetwork_type or unsupported \ref ctlnetwork_type in WIZCHIP \n
- * 0 : Success
- */
-int8_t ctlnetwork(ctlnetwork_type cntype, void* arg);
-
-
/*
* The following functions are implemented for internal use.
* but You can call these functions for code size reduction instead of ctlwizchip() and ctlnetwork().
@@ -376,20 +364,6 @@ void wizphy_getphystat(wiz_PhyConf* phyconf);
int8_t wizphy_setphypmode(uint8_t pmode);
/**
-* @ingroup extra_functions
- * @brief Set the network information for WIZCHIP
- * @param pnetinfo : @ref wizNetInfo
- */
-void wizchip_setnetinfo(wiz_NetInfo* pnetinfo);
-
-/**
- * @ingroup extra_functions
- * @brief Get the network information for WIZCHIP
- * @param pnetinfo : @ref wizNetInfo
- */
-void wizchip_getnetinfo(wiz_NetInfo* pnetinfo);
-
-/**
* @ingroup extra_functions
* @brief Set the network mode such WOL, PPPoE, Ping Block, and etc.
* @param pnetinfo Value of network mode. Refer to @ref netmode_type.
diff --git a/src/Networking/W5500Ethernet/Wiznet/Internet/DHCP/dhcp.cpp b/src/Networking/W5500Ethernet/Wiznet/Internet/DHCP/dhcp.cpp
index 2ecd0af3..9283d780 100644
--- a/src/Networking/W5500Ethernet/Wiznet/Internet/DHCP/dhcp.cpp
+++ b/src/Networking/W5500Ethernet/Wiznet/Internet/DHCP/dhcp.cpp
@@ -200,24 +200,22 @@ typedef struct {
} RIP_MSG;
+uint8_t DHCP_SOCKET; // Socket number for DHCP
-uint8_t DHCP_SOCKET; // Socket number for DHCP
-
-uint8_t DHCP_SIP[4]; // DHCP Server IP address
+IPAddress DHCP_SIP; // DHCP Server IP address
// Network information from DHCP Server
-uint8_t OLD_allocated_ip[4] = {0, }; // Previous IP address
-uint8_t DHCP_allocated_ip[4] = {0, }; // IP address from DHCP
-uint8_t DHCP_allocated_gw[4] = {0, }; // Gateway address from DHCP
-uint8_t DHCP_allocated_sn[4] = {0, }; // Subnet mask from DHCP
-uint8_t DHCP_allocated_dns[4] = {0, }; // DNS address from DHCP
-
+IPAddress OLD_allocated_ip; // Previous IP address
+IPAddress DHCP_allocated_ip; // IP address from DHCP
+IPAddress DHCP_allocated_gw; // Gateway address from DHCP
+IPAddress DHCP_allocated_sn; // Subnet mask from DHCP
+IPAddress DHCP_allocated_dns; // DNS address from DHCP
-DhcpState dhcp_state = DhcpState::init; // DHCP state
+DhcpState dhcp_state = DhcpState::init; // DHCP state
int8_t dhcp_retry_count;
uint32_t dhcp_lease_time;
-volatile uint32_t dhcp_tick_1s; // unit 1 second
+volatile uint32_t dhcp_tick_1s; // unit 1 second
uint32_t dhcp_tick_next;
uint32_t DHCP_XID; // Any number
@@ -416,11 +414,8 @@ void send_DHCP_DISCOVER(void)
}
// send broadcasting packet
- uint8_t ip[4];
- ip[0] = 255;
- ip[1] = 255;
- ip[2] = 255;
- ip[3] = 255;
+ IPAddress ip;
+ ip.SetBroadcast(); // 255.155.255.255
DEBUG_PRINTF("> Send DHCP_DISCOVER\n");
@@ -434,26 +429,20 @@ void send_DHCP_REQUEST(void)
makeDHCPMSG();
- uint8_t ip[4];
+ IPAddress ip;
if (dhcp_state == DhcpState::leased || dhcp_state == DhcpState::rerequest)
{
*((uint8_t*)(&pDHCPMSG->flags)) = ((DHCP_FLAGSUNICAST & 0xFF00)>> 8);
*((uint8_t*)(&pDHCPMSG->flags)+1) = (DHCP_FLAGSUNICAST & 0x00FF);
- pDHCPMSG->ciaddr[0] = DHCP_allocated_ip[0];
- pDHCPMSG->ciaddr[1] = DHCP_allocated_ip[1];
- pDHCPMSG->ciaddr[2] = DHCP_allocated_ip[2];
- pDHCPMSG->ciaddr[3] = DHCP_allocated_ip[3];
- ip[0] = DHCP_SIP[0];
- ip[1] = DHCP_SIP[1];
- ip[2] = DHCP_SIP[2];
- ip[3] = DHCP_SIP[3];
+ pDHCPMSG->ciaddr[0] = DHCP_allocated_ip.GetQuad(0);
+ pDHCPMSG->ciaddr[1] = DHCP_allocated_ip.GetQuad(1);
+ pDHCPMSG->ciaddr[2] = DHCP_allocated_ip.GetQuad(2);
+ pDHCPMSG->ciaddr[3] = DHCP_allocated_ip.GetQuad(3);
+ ip = DHCP_SIP;
}
else
{
- ip[0] = 255;
- ip[1] = 255;
- ip[2] = 255;
- ip[3] = 255;
+ ip.SetBroadcast(); // 255.255.255.255
}
size_t k = 4; // because MAGIC_COOKIE already made by makeDHCPMSG()
@@ -477,17 +466,17 @@ void send_DHCP_REQUEST(void)
{
pDHCPMSG->OPT[k++] = dhcpRequestedIPaddr;
pDHCPMSG->OPT[k++] = 0x04;
- pDHCPMSG->OPT[k++] = DHCP_allocated_ip[0];
- pDHCPMSG->OPT[k++] = DHCP_allocated_ip[1];
- pDHCPMSG->OPT[k++] = DHCP_allocated_ip[2];
- pDHCPMSG->OPT[k++] = DHCP_allocated_ip[3];
+ pDHCPMSG->OPT[k++] = DHCP_allocated_ip.GetQuad(0);
+ pDHCPMSG->OPT[k++] = DHCP_allocated_ip.GetQuad(1);
+ pDHCPMSG->OPT[k++] = DHCP_allocated_ip.GetQuad(2);
+ pDHCPMSG->OPT[k++] = DHCP_allocated_ip.GetQuad(3);
pDHCPMSG->OPT[k++] = dhcpServerIdentifier;
pDHCPMSG->OPT[k++] = 0x04;
- pDHCPMSG->OPT[k++] = DHCP_SIP[0];
- pDHCPMSG->OPT[k++] = DHCP_SIP[1];
- pDHCPMSG->OPT[k++] = DHCP_SIP[2];
- pDHCPMSG->OPT[k++] = DHCP_SIP[3];
+ pDHCPMSG->OPT[k++] = DHCP_SIP.GetQuad(0);
+ pDHCPMSG->OPT[k++] = DHCP_SIP.GetQuad(1);
+ pDHCPMSG->OPT[k++] = DHCP_SIP.GetQuad(2);
+ pDHCPMSG->OPT[k++] = DHCP_SIP.GetQuad(3);
}
// host name
@@ -548,17 +537,17 @@ void send_DHCP_DECLINE(void)
pDHCPMSG->OPT[k++] = dhcpRequestedIPaddr;
pDHCPMSG->OPT[k++] = 0x04;
- pDHCPMSG->OPT[k++] = DHCP_allocated_ip[0];
- pDHCPMSG->OPT[k++] = DHCP_allocated_ip[1];
- pDHCPMSG->OPT[k++] = DHCP_allocated_ip[2];
- pDHCPMSG->OPT[k++] = DHCP_allocated_ip[3];
+ pDHCPMSG->OPT[k++] = DHCP_allocated_ip.GetQuad(0);
+ pDHCPMSG->OPT[k++] = DHCP_allocated_ip.GetQuad(1);
+ pDHCPMSG->OPT[k++] = DHCP_allocated_ip.GetQuad(2);
+ pDHCPMSG->OPT[k++] = DHCP_allocated_ip.GetQuad(3);
pDHCPMSG->OPT[k++] = dhcpServerIdentifier;
pDHCPMSG->OPT[k++] = 0x04;
- pDHCPMSG->OPT[k++] = DHCP_SIP[0];
- pDHCPMSG->OPT[k++] = DHCP_SIP[1];
- pDHCPMSG->OPT[k++] = DHCP_SIP[2];
- pDHCPMSG->OPT[k++] = DHCP_SIP[3];
+ pDHCPMSG->OPT[k++] = DHCP_SIP.GetQuad(0);
+ pDHCPMSG->OPT[k++] = DHCP_SIP.GetQuad(1);
+ pDHCPMSG->OPT[k++] = DHCP_SIP.GetQuad(2);
+ pDHCPMSG->OPT[k++] = DHCP_SIP.GetQuad(3);
pDHCPMSG->OPT[k++] = endOption;
@@ -568,11 +557,8 @@ void send_DHCP_DECLINE(void)
}
//send broadcasting packet
- uint8_t ip[4];
- ip[0] = 0xFF;
- ip[1] = 0xFF;
- ip[2] = 0xFF;
- ip[3] = 0xFF;
+ IPAddress ip;
+ ip.SetBroadcast();
DEBUG_PRINTF("\n> Send DHCP_DECLINE\n");
@@ -627,31 +613,23 @@ int8_t parseDHCPMSG(void)
case subnetMask :
p++;
p++;
- DHCP_allocated_sn[0] = *p++;
- DHCP_allocated_sn[1] = *p++;
- DHCP_allocated_sn[2] = *p++;
- DHCP_allocated_sn[3] = *p++;
+ DHCP_allocated_sn.SetV4(*p);
+ p += 4;
break;
case routersOnSubnet :
{
p++;
const uint8_t opt_len = *p++;
- DHCP_allocated_gw[0] = *p++;
- DHCP_allocated_gw[1] = *p++;
- DHCP_allocated_gw[2] = *p++;
- DHCP_allocated_gw[3] = *p++;
- p = p + (opt_len - 4);
+ DHCP_allocated_gw.SetV4(p);
+ p += opt_len;
}
break;
case dns :
{
p++;
const uint8_t opt_len = *p++;
- DHCP_allocated_dns[0] = *p++;
- DHCP_allocated_dns[1] = *p++;
- DHCP_allocated_dns[2] = *p++;
- DHCP_allocated_dns[3] = *p++;
- p = p + (opt_len - 4);
+ DHCP_allocated_dns.SetV4(p);
+ p += opt_len;
}
break;
case dhcpIPaddrLeaseTime :
@@ -671,10 +649,8 @@ int8_t parseDHCPMSG(void)
{
p++;
p++;
- DHCP_SIP[0] = *p++;
- DHCP_SIP[1] = *p++;
- DHCP_SIP[2] = *p++;
- DHCP_SIP[3] = *p++;
+ DHCP_SIP.SetV4(p);
+ p += 4;
}
break;
@@ -720,10 +696,7 @@ DhcpRunResult DHCP_run(void)
switch (dhcp_state)
{
case DhcpState::init:
- DHCP_allocated_ip[0] = 0;
- DHCP_allocated_ip[1] = 0;
- DHCP_allocated_ip[2] = 0;
- DHCP_allocated_ip[3] = 0;
+ DHCP_allocated_ip.SetNull();
send_DHCP_DISCOVER();
dhcp_state = DhcpState::discover;
break;
@@ -732,10 +705,7 @@ DhcpRunResult DHCP_run(void)
if (type == DHCP_OFFER)
{
DEBUG_PRINTF("> Receive DHCP_OFFER\n");
- DHCP_allocated_ip[0] = pDHCPMSG->yiaddr[0];
- DHCP_allocated_ip[1] = pDHCPMSG->yiaddr[1];
- DHCP_allocated_ip[2] = pDHCPMSG->yiaddr[2];
- DHCP_allocated_ip[3] = pDHCPMSG->yiaddr[3];
+ DHCP_allocated_ip.SetV4(pDHCPMSG->yiaddr);
send_DHCP_REQUEST();
dhcp_state = DhcpState::request;
@@ -750,9 +720,9 @@ DhcpRunResult DHCP_run(void)
if (type == DHCP_ACK)
{
DEBUG_PRINTF("> Receive DHCP_ACK, lease time = %u\n", (unsigned int)dhcp_lease_time);
- uint8_t currentIp[4];
+ IPAddress currentIp;
getSIPR(currentIp);
- if (memcmp(DHCP_allocated_ip, currentIp, 4) == 0)
+ if (DHCP_allocated_ip == currentIp)
{
// We have been given the IP address we are already using.
// Don't check for an address conflict, because I have a suspicion that we end up replying to the ARP request ourselves.
@@ -813,10 +783,7 @@ DhcpRunResult DHCP_run(void)
if ((dhcp_lease_time != INFINITE_LEASETIME) && ((dhcp_lease_time/2) < dhcp_tick_1s))
{
DEBUG_PRINTF("> Maintain the IP address \n");
- OLD_allocated_ip[0] = DHCP_allocated_ip[0];
- OLD_allocated_ip[1] = DHCP_allocated_ip[1];
- OLD_allocated_ip[2] = DHCP_allocated_ip[2];
- OLD_allocated_ip[3] = DHCP_allocated_ip[3];
+ OLD_allocated_ip = DHCP_allocated_ip;
DHCP_XID++;
@@ -831,10 +798,7 @@ DhcpRunResult DHCP_run(void)
if (type == DHCP_ACK)
{
dhcp_retry_count = 0;
- if (OLD_allocated_ip[0] != DHCP_allocated_ip[0] ||
- OLD_allocated_ip[1] != DHCP_allocated_ip[1] ||
- OLD_allocated_ip[2] != DHCP_allocated_ip[2] ||
- OLD_allocated_ip[3] != DHCP_allocated_ip[3])
+ if (OLD_allocated_ip != DHCP_allocated_ip)
{
ret = DhcpRunResult::DHCP_IP_CHANGED;
dhcp_ip_update();
@@ -949,7 +913,7 @@ void DHCP_init(uint8_t s, uint32_t seed, const char *hname)
strncpy(HOST_NAME, hname, sizeof(HOST_NAME));
HOST_NAME[sizeof(HOST_NAME) - 1] = 0;
- uint8_t zeroip[4] = {0,0,0,0};
+ IPAddress zeroip;
getSHAR(DHCP_CHADDR);
DEBUG_PRINTF("MAC address: %02x:%02x:%02x:%02x:%02x:%02x\n", DHCP_CHADDR[0], DHCP_CHADDR[1], DHCP_CHADDR[2], DHCP_CHADDR[3], DHCP_CHADDR[4], DHCP_CHADDR[5]);
@@ -993,36 +957,24 @@ void DHCP_time_handler(void)
dhcp_tick_1s++;
}
-void getIPfromDHCP(uint8_t* ip)
+IPAddress getIPfromDHCP()
{
- ip[0] = DHCP_allocated_ip[0];
- ip[1] = DHCP_allocated_ip[1];
- ip[2] = DHCP_allocated_ip[2];
- ip[3] = DHCP_allocated_ip[3];
+ return DHCP_allocated_ip;
}
-void getGWfromDHCP(uint8_t* ip)
+IPAddress getGWfromDHCP()
{
- ip[0] =DHCP_allocated_gw[0];
- ip[1] =DHCP_allocated_gw[1];
- ip[2] =DHCP_allocated_gw[2];
- ip[3] =DHCP_allocated_gw[3];
+ return DHCP_allocated_gw;
}
-void getSNfromDHCP(uint8_t* ip)
+IPAddress getSNfromDHCP()
{
- ip[0] = DHCP_allocated_sn[0];
- ip[1] = DHCP_allocated_sn[1];
- ip[2] = DHCP_allocated_sn[2];
- ip[3] = DHCP_allocated_sn[3];
+ return DHCP_allocated_sn;
}
-void getDNSfromDHCP(uint8_t* ip)
+IPAddress getDNSfromDHCP()
{
- ip[0] = DHCP_allocated_dns[0];
- ip[1] = DHCP_allocated_dns[1];
- ip[2] = DHCP_allocated_dns[2];
- ip[3] = DHCP_allocated_dns[3];
+ return DHCP_allocated_dns;
}
uint32_t getDHCPLeasetime(void)
diff --git a/src/Networking/W5500Ethernet/Wiznet/Internet/DHCP/dhcp.h b/src/Networking/W5500Ethernet/Wiznet/Internet/DHCP/dhcp.h
index 6148b5eb..82701d36 100644
--- a/src/Networking/W5500Ethernet/Wiznet/Internet/DHCP/dhcp.h
+++ b/src/Networking/W5500Ethernet/Wiznet/Internet/DHCP/dhcp.h
@@ -118,22 +118,22 @@ void DHCP_stop(void);
* @brief Get IP address
* @param ip - IP address to be returned
*/
-void getIPfromDHCP(uint8_t* ip);
+IPAddress getIPfromDHCP();
/*
* @brief Get Gateway address
* @param ip - Gateway address to be returned
*/
-void getGWfromDHCP(uint8_t* ip);
+IPAddress getGWfromDHCP();
/*
* @brief Get Subnet mask value
* @param ip - Subnet mask to be returned
*/
-void getSNfromDHCP(uint8_t* ip);
+IPAddress getSNfromDHCP();
/*
* @brief Get DNS address
* @param ip - DNS address to be returned
*/
-void getDNSfromDHCP(uint8_t* ip);
+IPAddress getDNSfromDHCP();
/*
* @brief Get the leased time by DHCP sever
diff --git a/src/ObjectModel/ObjectModel.cpp b/src/ObjectModel/ObjectModel.cpp
index a278a219..fdbd79c9 100644
--- a/src/ObjectModel/ObjectModel.cpp
+++ b/src/ObjectModel/ObjectModel.cpp
@@ -7,7 +7,7 @@
#include "ObjectModel.h"
-#ifdef SUPPORT_OBJECT_MODEL
+#if SUPPORT_OBJECT_MODEL
#include "OutputMemory.h"
#include <cstring>
@@ -20,31 +20,23 @@ ObjectModel::ObjectModel()
// Report this object
bool ObjectModel::ReportAsJson(OutputBuffer* buf, const char* filter, ReportFlags flags)
{
- size_t numEntries;
- const ObjectModelTableEntry *tbl = GetObjectModelTable(numEntries);
- const char *moduleName = GetModuleName();
- if (moduleName != nullptr) // if we are not the root object
- {
- buf->cat(moduleName);
- buf->cat(':');
- filter = GetNextElement(filter); // skip the bit that matches the name of this module
- }
-
buf->cat('{');
+ size_t numEntries;
+ const ObjectModelTableEntry *omte = GetObjectModelTable(numEntries);
bool added = false;
while (numEntries != 0)
{
- if (added)
+ if (omte->Matches(filter, flags))
{
- buf->cat(',');
- }
- if (filter[0] == 0 || tbl->Matches(filter, flags))
- {
- tbl->ReportAsJson(buf, this, filter, flags);
+ if (added)
+ {
+ buf->cat(',');
+ }
+ omte->ReportAsJson(buf, this, filter, flags);
added = true;
}
--numEntries;
- ++tbl;
+ ++omte;
}
buf->cat('}');
return true;
@@ -197,89 +189,115 @@ const ObjectModelTableEntry *ObjectModelTableEntry::FindLeafEntry(ObjectModel *s
return ((ObjectModel*)param(self))->FindObjectModelLeafEntry(ObjectModel::GetNextElement(idString));
}
-// Add the value of this element to the buffer, returning true if it matched and we did
-bool ObjectModelTableEntry::ReportAsJson(OutputBuffer* buf, ObjectModel *self, const char* filter, ObjectModel::ReportFlags flags) const
+// Private function to report a value of primitive type
+void ObjectModelTableEntry::ReportItemAsJson(OutputBuffer *buf, const char *filter, ObjectModel::ReportFlags flags, void *nParam, TypeCode type)
{
- //TODO handle arrays
- buf->cat(name);
- buf->cat(':');
-
- if ((type & isArray) != 0)
- {
- //TODO
- buf->cat("[]");
- }
- else
+ switch (type)
{
- void *nParam = param(self);
- switch (type & 15)
- {
- case TYPE_OF(ObjectModel):
- ((ObjectModel*)nParam)->ReportAsJson(buf, filter, flags);
- break;
+ case TYPE_OF(ObjectModel):
+ ((ObjectModel*)nParam)->ReportAsJson(buf, filter, flags);
+ break;
+
+ case TYPE_OF(float):
+ buf->catf("%.1f", (double)*(const float *)nParam); //TODO different parameters need different number of decimal places
+ break;
+
+ case TYPE_OF(uint32_t):
+ buf->catf("%" PRIu32, *(const uint32_t *)nParam);
+ break;
- case TYPE_OF(float):
- buf->cat("%.1f", (double)*(const float *)nParam); //TODO different parameters need different number of decimal places
- break;
+ case TYPE_OF(int32_t):
+ buf->catf("%" PRIi32, *(const int32_t *)nParam);
+ break;
- case TYPE_OF(uint32_t):
- buf->cat("%" PRIu32, *(const uint32_t *)nParam);
- break;
+ case TYPE_OF(Bitmap32):
+ if (flags & ObjectModel::flagShortForm)
+ {
+ buf->catf("%" PRIu32, *(const uint32_t *)nParam);
+ }
+ else
+ {
+ buf->cat('[');
+ // TODO list the bits that are set
+ buf->cat(']');
+ }
+ break;
- case TYPE_OF(int32_t):
- buf->cat("%" PRIi32, *(const int32_t *)nParam);
- break;
+ case TYPE_OF(Enum32):
+ if (flags & ObjectModel::flagShortForm)
+ {
+ buf->catf("%" PRIu32, *(const uint32_t *)nParam);
+ }
+ else
+ {
+ buf->cat("\"unimplemented\"");
+ // TODO append the real name
+ }
+ break;
- case TYPE_OF(Bitmap32):
- if (flags & ObjectModel::shortForm)
+ case TYPE_OF(bool):
+ {
+ const bool bVal = *(const bool *)nParam;
+ if (flags & ObjectModel::flagShortForm)
{
- buf->cat("%" PRIu32, *(const uint32_t *)nParam);
+ buf->cat((bVal) ? '1' : '0');
}
else
{
- buf->cat('[');
- // TODO list the bits that are set
- buf->cat(']');
+ buf->cat((bVal) ? "yes" : "no");
}
- break;
+ }
+ break;
- case TYPE_OF(Enum32):
- if (flags & ObjectModel::shortForm)
- {
- buf->cat("%" PRIu32, *(const uint32_t *)nParam);
- }
- else
+ case TYPE_OF(IPAddress):
+ {
+ const IPAddress ipVal = *(const IPAddress *)nParam;
+ char sep = '"';
+ for (unsigned int q = 0; q < 4; ++q)
{
- buf->cat("\"unimplemented\"");
- // TODO append the real name
+ buf->catf("%c%u", sep, ipVal.GetQuad(q));
+ sep = '.';
}
- break;
+ buf->cat('"');
+ }
+ break;
+ }
+}
+
+// Add the value of this element to the buffer, returning true if it matched and we did
+bool ObjectModelTableEntry::ReportAsJson(OutputBuffer* buf, ObjectModel *self, const char* filter, ObjectModel::ReportFlags flags) const
+{
+ buf->cat(name);
+ buf->cat(':');
- case TYPE_OF(bool):
+ if ((type & IsArray) != 0)
+ {
+ // TODO match array indices
+ buf->cat('[');
+ const ObjectModelArrayDescriptor *arr = (const ObjectModelArrayDescriptor*)param(self);
+ for (size_t i = 0; i < arr->GetNumElements(self); ++i)
+ {
+ if (i != 0)
{
- const bool bVal = *(const bool *)nParam;
- if (flags & ObjectModel::shortForm)
- {
- buf->cat((bVal) ? '1' : '0');
- }
- else
- {
- buf->cat((bVal) ? "yes" : "no");
- }
+ buf->cat(',');
}
- break;
+ ReportItemAsJson(buf, filter, flags, arr->GetElement(self, i), type & ~IsArray);
}
+ buf->cat(']');
+ }
+ else
+ {
+ ReportItemAsJson(buf, filter, flags, param(self), type);
}
-
return true;
}
-// Compare and ID with the name of this object
+// Compare an ID with the name of this object
int ObjectModelTableEntry::IdCompare(const char *id) const
{
- if (id[0] == '*')
+ if (id[0] == 0 || id[0] == '*')
{
- return true;
+ return 0;
}
const char *n = name;
@@ -303,6 +321,99 @@ void* ObjectModelTableEntry::GetValuePointer(ObjectModel *self, TypeCode t) cons
return param(self);
}
+// Return the type of an object
+TypeCode ObjectModel::GetObjectType(const char *idString)
+{
+ const ObjectModelTableEntry * const e = FindObjectModelLeafEntry(idString);
+ return (e == nullptr) ? NoType : e->type;
+}
+
+// Get the value of an object when we don't know what its type is
+TypeCode ObjectModel::GetObjectValue(ExpressionValue& val, const char *idString)
+{
+ const ObjectModelTableEntry * const e = FindObjectModelLeafEntry(idString);
+ if (e == nullptr)
+ {
+ return NoType;
+ }
+ switch (e->type)
+ {
+ case TYPE_OF(float):
+ val.fVal = *((const float*)e->param(this));
+ break;
+
+ case TYPE_OF(uint32_t):
+ case TYPE_OF(Bitmap32):
+ case TYPE_OF(Enum32):
+ val.uVal = *((const uint32_t*)e->param(this));
+ break;
+
+ case TYPE_OF(int32_t):
+ val.iVal = *((const int32_t*)e->param(this));
+ break;
+
+ case TYPE_OF(const char*):
+ val.sVal = *((const char* const *)e->param(this));
+ break;
+
+ default:
+ break;
+ }
+ return e->type;
+}
+
+// Template specialisations
+template<> bool ObjectModel::GetObjectValue(float& val, const char *idString)
+{
+ const ObjectModelTableEntry * const e = FindObjectModelLeafEntry(idString);
+ if (e == nullptr)
+ {
+ return false;
+ }
+
+ switch (e->type)
+ {
+ case TYPE_OF(float):
+ val = *((const float*)e->param(this));
+ return true;
+
+ case TYPE_OF(uint32_t):
+ val = (float)*((const uint32_t*)e->param(this));
+ return true;
+
+ case TYPE_OF(int32_t):
+ val = (float)*((const int32_t*)e->param(this));
+ return true;
+
+ default:
+ return false;
+ }
+}
+
+// Specialisation of above for int, allowing conversion from unsigned to signed
+template<> bool ObjectModel::GetObjectValue(int32_t& val, const char *idString)
+{
+ const ObjectModelTableEntry * const e = FindObjectModelLeafEntry(idString);
+ if (e == nullptr)
+ {
+ return false;
+ }
+
+ switch (e->type)
+ {
+ case TYPE_OF(int32_t):
+ val = *((const int32_t*)e->param(this));
+ return true;
+
+ case TYPE_OF(uint32_t):
+ val = (int32_t)*((const uint32_t*)e->param(this));
+ return true;
+
+ default:
+ return false;
+ }
+}
+
#endif
// End
diff --git a/src/ObjectModel/ObjectModel.h b/src/ObjectModel/ObjectModel.h
index dddc6e21..d76f9ce5 100644
--- a/src/ObjectModel/ObjectModel.h
+++ b/src/ObjectModel/ObjectModel.h
@@ -9,25 +9,39 @@
#define SRC_OBJECTMODEL_OBJECTMODEL_H_
#include "RepRapFirmware.h"
+#include <General/IPAddress.h>
-#ifdef SUPPORT_OBJECT_MODEL
+#if SUPPORT_OBJECT_MODEL
typedef uint32_t ObjectModelFilterFlags;
typedef uint8_t TypeCode;
+constexpr TypeCode IsArray = 128; // this is or'ed in to a type code to indicate an array
+constexpr TypeCode NoType = 0; // code for an invalid or unknown type
+
+// Forward declarations
+class ObjectModelTableEntry;
+class ObjectModel;
+
+union ExpressionValue
+{
+ float fVal;
+ int32_t iVal;
+ uint32_t uVal;
+ const char *sVal;
+ const ObjectModel *omVal;
+};
// Dummy types, used to define type codes
class Bitmap32 { };
class Enum32 { };
-// Forward declarations
-class ObjectModelTableEntry;
-
class ObjectModel
{
public:
enum ReportFlags : uint16_t
{
- shortForm = 1
+ flagsNone,
+ flagShortForm = 1
};
ObjectModel();
@@ -35,6 +49,12 @@ public:
// Construct a JSON representation of those parts of the object model requested by the user
bool ReportAsJson(OutputBuffer *buf, const char *filter, ReportFlags rflags);
+ // Return the type of an object
+ TypeCode GetObjectType(const char *idString);
+
+ // Get the value of an object when we don't know what its type is
+ TypeCode GetObjectValue(ExpressionValue& val, const char *idString);
+
// Get values of various types from the object model, returning true if successful
template<class T> bool GetObjectValue(T& val, const char *idString);
@@ -68,7 +88,6 @@ public:
static const char* GetNextElement(const char *id);
protected:
- virtual const char *GetModuleName() const = 0;
virtual const ObjectModelTableEntry *GetObjectModelTable(size_t& numEntries) const = 0;
private:
@@ -81,6 +100,7 @@ private:
};
// Function template used to get constexpr type IDs
+// Each type must return a unique type code in the range 1 to 127
template<class T> constexpr TypeCode TypeOf();
template<> constexpr TypeCode TypeOf<bool> () { return 1; }
@@ -90,52 +110,75 @@ template<> constexpr TypeCode TypeOf<float>() { return 4; }
template<> constexpr TypeCode TypeOf<Bitmap32>() { return 5; }
template<> constexpr TypeCode TypeOf<Enum32>() { return 6; }
template<> constexpr TypeCode TypeOf<ObjectModel>() { return 7; }
+template<> constexpr TypeCode TypeOf<const char *>() { return 8; }
+template<> constexpr TypeCode TypeOf<IPAddress>() { return 9; }
#define TYPE_OF(_t) (TypeOf<_t>())
+// Entry to describe an array
+class ObjectModelArrayDescriptor
+{
+public:
+ size_t (*GetNumElements)(ObjectModel*);
+ void * (*GetElement)(ObjectModel*, size_t);
+};
+
// Object model table entry
// It must be possible to construct these in the form of initialised data in flash memory, to avoid using large amounts of RAM.
// Therefore we can't use a class hierarchy to represent different types of entry. Instead we use a type code and a void* parameter.
-// Only const member functions are allowed in this class
class ObjectModelTableEntry
{
public:
+ // Type declarations
+ // Flags field of a table entry
enum ObjectModelEntryFlags : uint16_t
{
- none = 0,
+ none = 0, // nothing special
live = 1, // fast changing data, included in common status response
canAlter = 2, // we can alter this value
- isArray = 4 // value is an array of the basic type
};
+ // Type of the function pointer in the table entry, that returns a pointer to the data
typedef void *(*ParamFuncPtr_t)(ObjectModel*);
+ // Member data. This must be public so that we can brace-initialise table entries.
+ const char * name; // name of this field
+ ParamFuncPtr_t param; // function that yields a pointer to this value
+ TypeCode type; // code for the type of this value
+ ObjectModelEntryFlags flags; // information about this value
+
+ // Member functions. These must all be 'const'.
+
// Return true if this object table entry matches a filter or query
bool Matches(const char *filter, ObjectModelFilterFlags flags) const;
- // Add the value of this element to the buffer, returning true if it matched and we did
+ // See whether we should add the value of this element to the buffer, returning true if it matched the filter and we did add it
bool ReportAsJson(OutputBuffer* buf, ObjectModel *self, const char* filter, ObjectModel::ReportFlags flags) const;
+ // Return the name of this field
const char* GetName() const { return name; }
+ // Compare the name of this field with the filter string that we are trying to match
int IdCompare(const char *id) const;
+ // Return true if this field is an object, not a primitive type
bool IsObject() const { return type == TYPE_OF(ObjectModel); }
+
+ // Follow the path specified by the ifString until we reach the end of it
const ObjectModelTableEntry *FindLeafEntry(ObjectModel *self, const char *idString) const;
- // Check the type is correct, call the function if necessary and return the pointer
+ // Check the type is correct, call the function and return the pointer
void* GetValuePointer(ObjectModel *self, TypeCode t) const;
- // Note: all data members must be public so that we can brace-initialise these. This doesn't matter because they are always 'const'.
- const char * name;
- ParamFuncPtr_t param;
- TypeCode type;
- ObjectModelEntryFlags flags;
+ // Private function to report a value of primitive type
+ static void ReportItemAsJson(OutputBuffer *buf, const char *filter, ObjectModel::ReportFlags flags, void *nParam, TypeCode type);
};
+// Function to retrieve a value by searching the object model
+// Returns true if success
template<class T> bool ObjectModel::GetObjectValue(T& val, const char *idString)
{
- const ObjectModelTableEntry *e = FindObjectModelLeafEntry(idString);
+ const ObjectModelTableEntry * const e = FindObjectModelLeafEntry(idString);
if (e == nullptr)
{
return false;
@@ -149,12 +192,42 @@ template<class T> bool ObjectModel::GetObjectValue(T& val, const char *idString)
return true;
}
+// Specialisation of above for float, allowing conversion from integer to float
+template<> bool ObjectModel::GetObjectValue(float& val, const char *idString);
+
+// Specialisation of above for int, allowing conversion from unsigned to signed
+template<> bool ObjectModel::GetObjectValue(int32_t& val, const char *idString);
+
template<class T> T* ObjectModel::GetObjectPointer(const char* idString)
{
const ObjectModelTableEntry *e = FindObjectModelLeafEntry(idString);
return (e == nullptr) ? nullptr : (T*)(e->GetValuePointer(this, TYPE_OF(T)));
}
+// Use this macro to inherit form ObjectModel
+#define INHERIT_OBJECT_MODEL : public ObjectModel
+
+// Use this macro in the 'protected' section of every class declaration that derived from ObjectModel
+#define DECLARE_OBJECT_MODEL \
+ const ObjectModelTableEntry *GetObjectModelTable(size_t& numEntries) const override; \
+ static const ObjectModelTableEntry objectModelTable[];
+
+#define DEFINE_GET_OBJECT_MODEL_TABLE(_class) \
+ const ObjectModelTableEntry *_class::GetObjectModelTable(size_t& numEntries) const \
+ { \
+ numEntries = ARRAY_SIZE(objectModelTable); \
+ return objectModelTable; \
+ }
+
+#define OBJECT_MODEL_FUNC_BODY(_class,_ret) [] (ObjectModel* arg) { _class * const self = static_cast<_class*>(arg); return (void *)(_ret); }
+#define OBJECT_MODEL_FUNC_NOSELF(_ret) [] (ObjectModel* arg) { return (void *)(_ret); }
+
+#else
+
+#define INHERIT_OBJECT_MODEL // nothing
+#define DECLARE_OBJECT_MODEL // nothing
+#define DEFINE_GET_OBJECT_MODEL_TABLE // nothing
+
#endif
#endif /* SRC_OBJECTMODEL_OBJECTMODEL_H_ */
diff --git a/src/Pins.h b/src/Pins.h
index 48900eaf..763023c1 100644
--- a/src/Pins.h
+++ b/src/Pins.h
@@ -86,6 +86,10 @@
# define SUPPORT_CAN_EXPANSION 0
#endif
+#ifndef SUPPORT_OBJECT_MODEL
+# define SUPPORT_OBJECT_MODEL 0
+#endif
+
#define HAS_SMART_DRIVERS (SUPPORT_TMC2660 || SUPPORT_TMC22xx || SUPPORT_TMC51xx)
#define HAS_STALL_DETECT (SUPPORT_TMC2660 || SUPPORT_TMC51xx)
diff --git a/src/Platform.cpp b/src/Platform.cpp
index 37a705b8..531a0e9c 100644
--- a/src/Platform.cpp
+++ b/src/Platform.cpp
@@ -73,28 +73,6 @@ extern uint32_t _estack; // defined in the linker script
# error Missing feature definition
#endif
-#if USE_CACHE
-
-#include "sam/drivers/cmcc/cmcc.h"
-
-inline void EnableCache()
-{
- cmcc_invalidate_all(CMCC);
- cmcc_enable(CMCC);
-}
-
-inline void DisableCache()
-{
- cmcc_disable(CMCC);
-}
-
-#else
-
-inline void EnableCache() {}
-inline void DisableCache() {}
-
-#endif
-
#if HAS_VOLTAGE_MONITOR
inline constexpr float AdcReadingToPowerVoltage(uint16_t adcVal)
@@ -261,9 +239,9 @@ void Platform::Init()
// File management
massStorage->Init();
- ARRAY_INIT(ipAddress, DefaultIpAddress);
- ARRAY_INIT(netMask, DefaultNetMask);
- ARRAY_INIT(gateWay, DefaultGateway);
+ ipAddress = DefaultIpAddress;
+ netMask = DefaultNetMask;
+ gateWay = DefaultGateway;
#if SAM4E || SAM4S || SAME70
// Read the unique ID of the MCU
@@ -367,8 +345,11 @@ void Platform::Init()
InitZProbe(); // this also sets up zProbeModulationPin
// AXES
- ARRAY_INIT(axisMaxima, AXIS_MAXIMA);
- ARRAY_INIT(axisMinima, AXIS_MINIMA);
+ for (size_t axis = 0; axis < MaxAxes; ++axis)
+ {
+ axisMinima[axis] = 0.0;
+ axisMaxima[axis] = 200.0;
+ }
axisMaximaProbed = axisMinimaProbed = 0;
idleCurrentFactor = DefaultIdleCurrentFactor;
@@ -510,7 +491,7 @@ void Platform::Init()
# else
SmartDrivers::Init(ENABLE_PINS, numSmartDrivers);
# endif
- temperatureShutdownDrivers = temperatureWarningDrivers = shortToGroundDrivers = openLoadADrivers = openLoadBDrivers = 0;
+ temperatureShutdownDrivers = temperatureWarningDrivers = shortToGroundDrivers = openLoadADrivers = openLoadBDrivers = notOpenLoadADrivers = notOpenLoadBDrivers = 0;
#endif
#if HAS_STALL_DETECT
@@ -681,10 +662,10 @@ void Platform::InitZProbe()
pinMode(zProbeModulationPin, OUTPUT_LOW); // enable the alternate sensor
break;
- case ZProbeType::e0Switch:
+ case ZProbeType::endstopSwitch:
AnalogInEnableChannel(zProbeAdcChannel, false);
- pinMode(zProbePin, INPUT_PULLUP);
- pinMode(GetEndstopPin(E0_AXIS), INPUT);
+ pinMode(zProbePin, INPUT_PULLUP); // don't leave it floating
+ pinMode(GetEndstopPin(GetCurrentZProbeParameters().inputChannel), INPUT);
pinMode(zProbeModulationPin, OUTPUT_LOW); // we now set the modulation output high during probing only when using probe types 4 and higher
break;
@@ -697,20 +678,6 @@ void Platform::InitZProbe()
pinMode(zProbePin, INPUT_PULLUP);
pinMode(zProbeModulationPin, OUTPUT_LOW); // we now set the modulation output high during probing only when using probe types 4 and higher
break;
-
- case ZProbeType::e1Switch:
- AnalogInEnableChannel(zProbeAdcChannel, false);
- pinMode(zProbePin, INPUT_PULLUP);
- pinMode(GetEndstopPin(E0_AXIS + 1), INPUT);
- pinMode(zProbeModulationPin, OUTPUT_LOW); // we now set the modulation output high during probing only when using probe types 4 and higher
- break;
-
- case ZProbeType::zSwitch:
- AnalogInEnableChannel(zProbeAdcChannel, false);
- pinMode(zProbePin, INPUT_PULLUP);
- pinMode(endStopPins[Z_AXIS], INPUT);
- pinMode(zProbeModulationPin, OUTPUT_LOW); // we now set the modulation output high during probing only when using probe types 4 and higher
- break;
}
}
@@ -725,10 +692,8 @@ int Platform::GetZProbeReading() const
{
case ZProbeType::analog: // Simple or intelligent IR sensor
case ZProbeType::alternateAnalog: // Alternate sensor
- case ZProbeType::e0Switch: // Switch connected to E0 endstop input
+ case ZProbeType::endstopSwitch: // Switch connected to an endstop input
case ZProbeType::digital: // Switch connected to Z probe input
- case ZProbeType::e1Switch: // Switch connected to E1 endstop input
- case ZProbeType::zSwitch: // Switch connected to Z endstop input
zProbeVal = (int) ((zProbeOnFilter.GetSum() + zProbeOffFilter.GetSum()) / (8 * Z_PROBE_AVERAGE_READINGS));
break;
@@ -829,9 +794,10 @@ void Platform::SetZProbeType(unsigned int pt)
void Platform::SetProbing(bool isProbing)
{
- if (zProbeType > ZProbeType::alternateAnalog)
+ // For Z probe types other than 1/2/3 and bltouch we set the modulation pin high at the start of a probing move and low at the end
+ // Don't do this for bltouch because on the Maestro, the MOD pin is normally used as the servo control output
+ if (zProbeType > ZProbeType::alternateAnalog && zProbeType != ZProbeType::blTouch)
{
- // For Z probe types other than 1/2/3 we set the modulation pin high at the start of a probing move and low at the end
digitalWrite(zProbeModulationPin, isProbing);
}
}
@@ -849,9 +815,7 @@ const ZProbe& Platform::GetZProbeParameters(ZProbeType probeType) const
return irZProbeParameters;
case ZProbeType::alternateAnalog:
return alternateZProbeParameters;
- case ZProbeType::e0Switch:
- case ZProbeType::e1Switch:
- case ZProbeType::zSwitch:
+ case ZProbeType::endstopSwitch:
default:
return switchZProbeParameters;
}
@@ -874,9 +838,7 @@ void Platform::SetZProbeParameters(ZProbeType probeType, const ZProbe& params)
alternateZProbeParameters = params;
break;
- case ZProbeType::e0Switch:
- case ZProbeType::e1Switch:
- case ZProbeType::zSwitch:
+ case ZProbeType::endstopSwitch:
default:
switchZProbeParameters = params;
break;
@@ -1244,28 +1206,22 @@ void Platform::SetEmulating(Compatibility c)
}
}
-void Platform::UpdateNetworkAddress(uint8_t dst[4], const uint8_t src[4])
+void Platform::SetIPAddress(IPAddress ip)
{
- for (uint8_t i = 0; i < 4; i++)
- {
- dst[i] = src[i];
- }
+ ipAddress = ip;
reprap.GetNetwork().SetEthernetIPAddress(ipAddress, gateWay, netMask);
}
-void Platform::SetIPAddress(uint8_t ip[])
-{
- UpdateNetworkAddress(ipAddress, ip);
-}
-
-void Platform::SetGateWay(uint8_t gw[])
+void Platform::SetGateWay(IPAddress gw)
{
- UpdateNetworkAddress(gateWay, gw);
+ gateWay = gw;
+ reprap.GetNetwork().SetEthernetIPAddress(ipAddress, gateWay, netMask);
}
-void Platform::SetNetMask(uint8_t nm[])
+void Platform::SetNetMask(IPAddress nm)
{
- UpdateNetworkAddress(netMask, nm);
+ netMask = nm;
+ reprap.GetNetwork().SetEthernetIPAddress(ipAddress, gateWay, netMask);
}
// Flush messages to aux, returning true if there is more to send
@@ -1458,28 +1414,38 @@ void Platform::Spin()
// Also, false open load indications persist when in standstill, if the phase has zero current in that position
if ((stat & TMC_RR_OLA) != 0)
{
- if (openLoadADrivers == 0)
+ if (!openLoadATimer.IsRunning())
{
openLoadATimer.Start();
+ openLoadADrivers = notOpenLoadADrivers = 0;
}
openLoadADrivers |= mask;
}
- else
+ else if (openLoadATimer.IsRunning())
{
- openLoadADrivers &= ~mask;
+ notOpenLoadADrivers |= mask;
+ if ((openLoadADrivers & ~notOpenLoadADrivers) == 0)
+ {
+ openLoadATimer.Stop();
+ }
}
if ((stat & TMC_RR_OLB) != 0)
{
- if (openLoadBDrivers == 0)
+ if (!openLoadBTimer.IsRunning())
{
openLoadBTimer.Start();
+ openLoadBDrivers = notOpenLoadBDrivers = 0;
}
openLoadBDrivers |= mask;
}
- else
+ else if (openLoadBTimer.IsRunning())
{
- openLoadBDrivers &= ~mask;
+ notOpenLoadBDrivers |= mask;
+ if ((openLoadBDrivers & ~notOpenLoadBDrivers) == 0)
+ {
+ openLoadBTimer.Stop();
+ }
}
#if HAS_STALL_DETECT
@@ -1583,11 +1549,11 @@ void Platform::Spin()
ReportDrivers(ErrorMessage, temperatureShutdownDrivers, "over temperature shutdown", reported);
if (openLoadATimer.CheckAndStop(OpenLoadTimeout))
{
- ReportDrivers(ErrorMessage, openLoadADrivers, "motor phase A disconnected", reported);
+ ReportDrivers(WarningMessage, openLoadADrivers, "motor phase A may be disconnected", reported);
}
if (openLoadBTimer.CheckAndStop(OpenLoadTimeout))
{
- ReportDrivers(ErrorMessage, openLoadBDrivers, "motor phase B disconnected", reported);
+ ReportDrivers(WarningMessage, openLoadBDrivers, "motor phase B may be disconnected", reported);
}
// Don't warn about a hot driver if we recently turned on a fan to cool it
@@ -1723,7 +1689,7 @@ void Platform::ReportDrivers(MessageType mt, DriversBitmap& whichDrivers, const
if (whichDrivers != 0)
{
String<ScratchStringLength> scratchString;
- scratchString.printf("%s on drivers", text);
+ scratchString.printf("%s reported by driver(s)", text);
DriversBitmap wd = whichDrivers;
for (unsigned int drive = 0; wd != 0; ++drive)
{
@@ -1752,7 +1718,7 @@ bool Platform::AnyAxisMotorStalled(size_t drive) const
for (size_t i = 0; i < axisDrivers[drive].numDrivers; ++i)
{
const uint8_t driver = axisDrivers[drive].driverNumbers[i];
- if (driver < NumDirectDrivers && (SmartDrivers::GetLiveStatus(driver) & TMC_RR_SG) != 0)
+ if (driver < numSmartDrivers && (SmartDrivers::GetLiveStatus(driver) & TMC_RR_SG) != 0)
{
return true;
}
@@ -2720,6 +2686,15 @@ EndStopHit Platform::Stopped(size_t drive) const
: AnyAxisMotorStalled(drive);
break;
+ case KinematicsType::coreXYUV:
+ // Both X and Y motors are involved in homing X or Y, and both U and V motors are involved in homing U and V
+ motorIsStalled = (drive == X_AXIS || drive == Y_AXIS)
+ ? AnyAxisMotorStalled(X_AXIS) || AnyAxisMotorStalled(Y_AXIS)
+ : (drive == U_AXIS || drive == V_AXIS)
+ ? AnyAxisMotorStalled(U_AXIS) || AnyAxisMotorStalled(V_AXIS)
+ : AnyAxisMotorStalled(drive);
+ break;
+
case KinematicsType::coreXZ:
// Both X and Z motors are involved in homing X or Z
motorIsStalled = (drive == X_AXIS || drive == Z_AXIS)
@@ -4413,7 +4388,7 @@ float Platform::GetTmcDriversTemperature(unsigned int board) const
#if HAS_STALL_DETECT
// Configure the motor stall detection, returning true if an error was encountered
-bool Platform::ConfigureStallDetection(GCodeBuffer& gb, const StringRef& reply)
+GCodeResult Platform::ConfigureStallDetection(GCodeBuffer& gb, const StringRef& reply, OutputBuffer *& buf)
{
// Build a bitmap of all the drivers referenced
// First looks for explicit driver numbers
@@ -4428,7 +4403,7 @@ bool Platform::ConfigureStallDetection(GCodeBuffer& gb, const StringRef& reply)
if (drives[i] >= numSmartDrivers)
{
reply.printf("Invalid drive number '%" PRIu32 "'", drives[i]);
- return true;
+ return GCodeResult::error;
}
SetBit(drivers, drives[i]);
}
@@ -4446,6 +4421,21 @@ bool Platform::ConfigureStallDetection(GCodeBuffer& gb, const StringRef& reply)
}
}
+ // Look for extruders
+ if (gb.Seen('E'))
+ {
+ uint32_t extruderNumbers[MaxExtruders];
+ size_t numSeen = MaxExtruders;
+ gb.GetUnsignedArray(extruderNumbers, numSeen, false);
+ for (size_t i = 0; i < numSeen; ++i)
+ {
+ if (extruderNumbers[i] < MaxExtruders)
+ {
+ SetBit(drivers, GetExtruderDriver(extruderNumbers[i]));
+ }
+ }
+ }
+
// Now check for values to change
bool seen = false;
if (gb.Seen('S'))
@@ -4529,35 +4519,46 @@ bool Platform::ConfigureStallDetection(GCodeBuffer& gb, const StringRef& reply)
}
}
- if (!seen)
+ if (seen)
{
- if (drivers == 0)
- {
- drivers = LowestNBits<DriversBitmap>(numSmartDrivers);
- }
- bool printed = false;
- for (size_t drive = 0; drive < numSmartDrivers; ++drive)
+ return GCodeResult::ok;
+ }
+
+ // Print the stall status
+ if (!OutputBuffer::Allocate(buf))
+ {
+ return GCodeResult::notFinished;
+ }
+
+ if (drivers == 0)
+ {
+ drivers = LowestNBits<DriversBitmap>(numSmartDrivers);
+ }
+
+ bool printed = false;
+ for (size_t drive = 0; drive < numSmartDrivers; ++drive)
+ {
+ if (IsBitSet(drivers, drive))
{
- if (IsBitSet(drivers, drive))
+ if (printed)
{
- if (printed)
- {
- reply.cat('\n');
- }
- reply.catf("Driver %u: ", drive);
- SmartDrivers::AppendStallConfig(drive, reply);
- reply.catf(", action: %s",
- (IsBitSet(rehomeOnStallDrivers, drive)) ? "rehome"
- : (IsBitSet(pauseOnStallDrivers, drive)) ? "pause"
- : (IsBitSet(logOnStallDrivers, drive)) ? "log"
- : "none"
- );
- printed = true;
+ buf->cat('\n');
}
+ buf->catf("Driver %u: ", drive);
+ reply.Clear(); // we use 'reply' as a temporary buffer
+ SmartDrivers::AppendStallConfig(drive, reply);
+ buf->cat(reply.c_str());
+ buf->catf(", action: %s",
+ (IsBitSet(rehomeOnStallDrivers, drive)) ? "rehome"
+ : (IsBitSet(pauseOnStallDrivers, drive)) ? "pause"
+ : (IsBitSet(logOnStallDrivers, drive)) ? "log"
+ : "none"
+ );
+ printed = true;
}
-
}
- return false;
+
+ return GCodeResult::ok;
}
#endif
diff --git a/src/Platform.h b/src/Platform.h
index a12c93e6..9bdc2630 100644
--- a/src/Platform.h
+++ b/src/Platform.h
@@ -42,6 +42,7 @@ Licence: GPL
#include "Spindle.h"
#include "ZProbe.h"
#include "ZProbeProgrammer.h"
+#include <General/IPAddress.h>
#if defined(DUET_NG)
# include "DueXn.h"
@@ -85,11 +86,6 @@ const int INKJET_DELAY_MICROSECONDS = 800; // How long to wait before the nex
#endif
-// AXES
-
-const float AXIS_MINIMA[MaxAxes] = AXES_(0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0); // mm
-const float AXIS_MAXIMA[MaxAxes] = AXES_(230.0, 210.0, 200.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0); // mm
-
// Z PROBE
constexpr float Z_PROBE_STOP_HEIGHT = 0.7; // Millimetres
@@ -347,12 +343,12 @@ public:
bool HaveAux() const { return auxDetected; } // Any device on the AUX line?
void SetAuxDetected() { auxDetected = true; }
- void SetIPAddress(uint8_t ip[]);
- const uint8_t* GetIPAddress() const;
- void SetNetMask(uint8_t nm[]);
- const uint8_t* NetMask() const;
- void SetGateWay(uint8_t gw[]);
- const uint8_t* GateWay() const;
+ void SetIPAddress(IPAddress ip);
+ IPAddress GetIPAddress() const;
+ void SetNetMask(IPAddress nm);
+ IPAddress NetMask() const;
+ void SetGateWay(IPAddress gw);
+ IPAddress GateWay() const;
void SetBaudRate(size_t chan, uint32_t br);
uint32_t GetBaudRate(size_t chan) const;
void SetCommsProperties(size_t chan, uint32_t cp);
@@ -554,7 +550,7 @@ public:
#endif
#if HAS_STALL_DETECT
- bool ConfigureStallDetection(GCodeBuffer& gb, const StringRef& reply);
+ GCodeResult ConfigureStallDetection(GCodeBuffer& gb, const StringRef& reply, OutputBuffer *& buf);
#endif
// User I/O and servo support
@@ -683,9 +679,9 @@ private:
ZProbeType zProbeType; // the type of Z probe we are currently using
// Network
- uint8_t ipAddress[4];
- uint8_t netMask[4];
- uint8_t gateWay[4];
+ IPAddress ipAddress;
+ IPAddress netMask;
+ IPAddress gateWay;
uint8_t defaultMacAddress[6];
// Board and processor
@@ -735,7 +731,8 @@ private:
#if HAS_SMART_DRIVERS
size_t numSmartDrivers; // the number of TMC2660 drivers we have, the remaining are simple enable/step/dir drivers
- DriversBitmap temperatureShutdownDrivers, temperatureWarningDrivers, shortToGroundDrivers, openLoadADrivers, openLoadBDrivers;
+ DriversBitmap temperatureShutdownDrivers, temperatureWarningDrivers, shortToGroundDrivers;
+ DriversBitmap openLoadADrivers, openLoadBDrivers, notOpenLoadADrivers, notOpenLoadBDrivers;
MillisTimer openLoadATimer, openLoadBTimer;
MillisTimer driversFanTimers[NumTmcDriversSenseChannels]; // driver cooling fan timers
uint8_t nextDriveToPoll;
@@ -778,7 +775,6 @@ private:
void InitZProbe();
uint16_t GetRawZProbeReading() const;
- void UpdateNetworkAddress(uint8_t dst[4], const uint8_t src[4]);
// Axes and endstops
float axisMaxima[MaxAxes];
@@ -1101,17 +1097,17 @@ inline void Platform::SetHeatSampleTime(float st)
}
}
-inline const uint8_t* Platform::GetIPAddress() const
+inline IPAddress Platform::GetIPAddress() const
{
return ipAddress;
}
-inline const uint8_t* Platform::NetMask() const
+inline IPAddress Platform::NetMask() const
{
return netMask;
}
-inline const uint8_t* Platform::GateWay() const
+inline IPAddress Platform::GateWay() const
{
return gateWay;
}
@@ -1131,9 +1127,9 @@ inline uint16_t Platform::GetRawZProbeReading() const
case ZProbeType::alternateAnalog:
return min<uint16_t>(AnalogInReadChannel(zProbeAdcChannel), 4000);
- case ZProbeType::e0Switch:
+ case ZProbeType::endstopSwitch:
{
- const bool b = IoPort::ReadPin(GetEndstopPin(E0_AXIS));
+ const bool b = IoPort::ReadPin(GetEndstopPin(GetCurrentZProbeParameters().inputChannel));
return (b) ? 4000 : 0;
}
@@ -1142,18 +1138,6 @@ inline uint16_t Platform::GetRawZProbeReading() const
case ZProbeType::blTouch:
return (IoPort::ReadPin(zProbePin)) ? 4000 : 0;
- case ZProbeType::e1Switch:
- {
- const bool b = IoPort::ReadPin(GetEndstopPin(E0_AXIS + 1));
- return (b) ? 4000 : 0;
- }
-
- case ZProbeType::zSwitch:
- {
- const bool b = IoPort::ReadPin(endStopPins[Z_AXIS]);
- return (b) ? 4000 : 0;
- }
-
case ZProbeType::zMotorStall:
default:
return 4000;
diff --git a/src/RepRap.cpp b/src/RepRap.cpp
index 64f520ba..db52a357 100644
--- a/src/RepRap.cpp
+++ b/src/RepRap.cpp
@@ -148,30 +148,27 @@ extern "C" void hsmciIdle(uint32_t stBits, uint32_t dmaBits)
#endif
-#ifdef SUPPORT_OBJECT_MODEL
+#if SUPPORT_OBJECT_MODEL
// Object model table and functions
-// Note: if using GCC version 7.3.1 20180622 then if lambda functions are used in this table, you must compile this file with option -std=gnu++17.
+// Note: if using GCC version 7.3.1 20180622 and lambda functions are used in this table, you must compile this file with option -std=gnu++17.
// Otherwise the table will be allocate in RAM instead of flash, which wastes too much RAM.
// Macro to build a standard lambda function that includes the necessary type conversions
-#define OBJECT_MODEL_FUNC(_ret) [] (ObjectModel* arg) { RepRap * const self = static_cast<RepRap*>(arg); return (void *)(_ret); }
+#define OBJECT_MODEL_FUNC(_ret) OBJECT_MODEL_FUNC_BODY(RepRap, _ret)
const ObjectModelTableEntry RepRap::objectModelTable[] =
{
- { "gcodes", OBJECT_MODEL_FUNC(&(self->GetGCodes())), TYPE_OF(ObjectModel), ObjectModelTableEntry::none }
+ // These entries are temporary pending design of the object model
+ //TODO design the object model
+ { "gcodes", OBJECT_MODEL_FUNC(&(self->GetGCodes())), TYPE_OF(ObjectModel), ObjectModelTableEntry::none },
+ { "move", OBJECT_MODEL_FUNC(&(self->GetMove())), TYPE_OF(ObjectModel), ObjectModelTableEntry::none },
+ { "network", OBJECT_MODEL_FUNC(&(self->GetNetwork())), TYPE_OF(ObjectModel), ObjectModelTableEntry::none },
+ { "meshProbe", OBJECT_MODEL_FUNC(&(self->GetMove().GetGrid())), TYPE_OF(ObjectModel), ObjectModelTableEntry::none },
+ { "randomProbe", OBJECT_MODEL_FUNC(&(self->GetMove().GetProbePoints())), TYPE_OF(ObjectModel), ObjectModelTableEntry::none },
};
-const char *RepRap::GetModuleName() const
-{
- return nullptr; // this module has no name and doesn't need one
-}
-
-const ObjectModelTableEntry *RepRap::GetObjectModelTable(size_t& numEntries) const
-{
- numEntries = ARRAY_SIZE(objectModelTable);
- return objectModelTable;
-}
+DEFINE_GET_OBJECT_MODEL_TABLE(RepRap)
#endif
@@ -2063,7 +2060,6 @@ bool RepRap::GetFileInfoResponse(const char *filename, OutputBuffer *&response,
{
if (!OutputBuffer::Allocate(response))
{
- // Should never happen
return false;
}
@@ -2078,7 +2074,6 @@ bool RepRap::GetFileInfoResponse(const char *filename, OutputBuffer *&response,
{
if (!OutputBuffer::Allocate(response))
{
- // Should never happen
return false;
}
diff --git a/src/RepRap.h b/src/RepRap.h
index aa5deb1d..9cd30f59 100644
--- a/src/RepRap.h
+++ b/src/RepRap.h
@@ -33,10 +33,7 @@ enum class ResponseSource
Generic
};
-class RepRap
-#ifdef SUPPORT_OBJECT_MODEL
- : public ObjectModel
-#endif
+class RepRap INHERIT_OBJECT_MODEL
{
public:
RepRap();
@@ -125,13 +122,8 @@ public:
void KickHeatTaskWatchdog() { heatTaskIdleTicks = 0; }
#endif
-#ifdef SUPPORT_OBJECT_MODEL
protected:
- const char *GetModuleName() const override;
- const ObjectModelTableEntry *GetObjectModelTable(size_t& numEntries) const override;
-
- static const ObjectModelTableEntry objectModelTable[];
-#endif
+ DECLARE_OBJECT_MODEL
private:
static void EncodeString(StringRef& response, const char* src, size_t spaceToLeave, bool allowControlChars = false, char prefix = 0);
diff --git a/src/RepRapFirmware.cpp b/src/RepRapFirmware.cpp
index 929001a1..31296ce3 100644
--- a/src/RepRapFirmware.cpp
+++ b/src/RepRapFirmware.cpp
@@ -191,6 +191,7 @@ const char * const moduleName[] =
"DuetExpansion",
"FilamentSensors",
"WiFi",
+ "Display",
"none"
};
@@ -291,14 +292,14 @@ int StringContains(const char* string, const char* match)
int i = 0;
int count = 0;
- while(string[i])
+ while (string[i] != 0)
{
if (string[i++] == match[count])
{
count++;
- if (!match[count])
+ if (match[count] == 0)
{
- return i;
+ return i - count;
}
}
else
diff --git a/src/Storage/FileStore.cpp b/src/Storage/FileStore.cpp
index 984248d1..45474d16 100644
--- a/src/Storage/FileStore.cpp
+++ b/src/Storage/FileStore.cpp
@@ -104,7 +104,7 @@ bool FileStore::Open(const char* directory, const char* fileName, OpenMode mode)
// It is up to the caller to report an error if necessary.
if (reprap.Debug(modulePlatform))
{
- reprap.GetPlatform().MessageF(ErrorMessage, "Can't open %s to %s, error code %d\n", location.c_str(), (writing) ? "write" : "read", (int)openReturn);
+ reprap.GetPlatform().MessageF(WarningMessage, "Failed to open %s to %s, error code %d\n", location.c_str(), (writing) ? "write" : "read", (int)openReturn);
}
return false;
}
diff --git a/src/Storage/FileStore.h b/src/Storage/FileStore.h
index 8626974d..7f723bfc 100644
--- a/src/Storage/FileStore.h
+++ b/src/Storage/FileStore.h
@@ -32,7 +32,11 @@ public:
bool Open(const char* directory, const char* fileName, OpenMode mode);
bool Read(char& b); // Read 1 byte
+ bool Read(uint8_t& b)
+ { return Read((char&)b); } // Read 1 byte
int Read(char* buf, size_t nBytes); // Read a block of nBytes length
+ int Read(uint8_t* buf, size_t nBytes)
+ { return Read((char*)buf, nBytes); } // Read a block of nBytes length
int ReadLine(char* buf, size_t nBytes); // As Read but stop after '\n' or '\r\n' and null-terminate
FileWriteBuffer *GetWriteBuffer() const; // Return a pointer to the remaining space for writing
bool Write(char b); // Write 1 byte
diff --git a/src/Storage/MassStorage.cpp b/src/Storage/MassStorage.cpp
index 8dcb25f9..a56a15d9 100644
--- a/src/Storage/MassStorage.cpp
+++ b/src/Storage/MassStorage.cpp
@@ -268,7 +268,7 @@ bool MassStorage::FindNext(FileInfo &file_info)
return true;
}
-// Quit searching for files. Needed to avoid hanging on to the mutex.
+// Quit searching for files. Needed to avoid hanging on to the mutex. Safe to call even if the caller doesn't hold the mutex.
void MassStorage::AbandonFindNext()
{
if (dirMutex.GetHolder() == RTOSIface::GetCurrentTask())
diff --git a/src/Tasks.cpp b/src/Tasks.cpp
index 26567b43..f926c47f 100644
--- a/src/Tasks.cpp
+++ b/src/Tasks.cpp
@@ -15,6 +15,10 @@
# include "task.h"
#endif
+#if USE_CACHE
+# include "cmcc/cmcc.h"
+#endif
+
const uint8_t memPattern = 0xA5;
extern "C" char *sbrk(int i);
@@ -77,7 +81,7 @@ extern "C" void AppMain()
#if USE_CACHE
// Enable the cache
- struct cmcc_config g_cmcc_cfg;
+ cmcc_config g_cmcc_cfg;
cmcc_get_config_defaults(&g_cmcc_cfg);
cmcc_init(CMCC, &g_cmcc_cfg);
EnableCache();
diff --git a/src/Tasks.h b/src/Tasks.h
index 704fa0e1..57474f82 100644
--- a/src/Tasks.h
+++ b/src/Tasks.h
@@ -12,6 +12,29 @@
#include "MessageType.h"
#include "RTOSIface/RTOSIface.h"
+#if USE_CACHE
+
+#include "sam/drivers/cmcc/cmcc.h"
+
+inline void EnableCache()
+{
+ cmcc_invalidate_all(CMCC);
+ cmcc_enable(CMCC);
+}
+
+inline void DisableCache()
+{
+ cmcc_disable(CMCC);
+}
+
+#else
+
+inline void EnableCache() {}
+inline void DisableCache() {}
+
+#endif
+
+
namespace Tasks
{
void Diagnostics(MessageType mtype);
diff --git a/src/Version.h b/src/Version.h
index 03427a1c..0aef939b 100644
--- a/src/Version.h
+++ b/src/Version.h
@@ -22,7 +22,7 @@
#endif
#ifndef DATE
-# define DATE "2018-09-23b0"
+# define DATE "2018-10-16b3"
#endif
#define AUTHORS "reprappro, dc42, chrishamm, t3p3, dnewman, printm3d"
diff --git a/src/ZProbe.cpp b/src/ZProbe.cpp
index dcc6d4fb..f5ce9b86 100644
--- a/src/ZProbe.cpp
+++ b/src/ZProbe.cpp
@@ -23,6 +23,7 @@ void ZProbe::Init(float h)
recoveryTime = 0.0;
tolerance = DefaultZProbeTolerance;
maxTaps = DefaultZProbeTaps;
+ inputChannel = 0;
invertReading = turnHeatersOff = false;
}
diff --git a/src/ZProbe.h b/src/ZProbe.h
index 75c43f80..9f3c3091 100644
--- a/src/ZProbe.h
+++ b/src/ZProbe.h
@@ -16,10 +16,10 @@ enum class ZProbeType : uint8_t
analog = 1,
dumbModulated = 2,
alternateAnalog = 3,
- e0Switch = 4,
+ endstopSwitch = 4,
digital = 5,
- e1Switch = 6,
- zSwitch = 7,
+ e1Switch_obsolete = 6,
+ zSwitch_obsolete = 7,
unfilteredDigital = 8,
blTouch = 9,
zMotorStall = 10,
@@ -40,6 +40,7 @@ public:
float recoveryTime; // Z probe recovery time
float tolerance; // maximum difference between probe heights when doing >1 taps
uint8_t maxTaps; // maximum probes at each point
+ uint8_t inputChannel; // input channel, use when the selected Z probe type is a switch
bool invertReading; // true if we need to invert the reading
bool turnHeatersOff; // true to turn heaters off while probing